@@ -9,8 +9,10 @@ project(test_topic)
|
|||||||
## is used, also find other catkin packages
|
## is used, also find other catkin packages
|
||||||
find_package(catkin REQUIRED COMPONENTS
|
find_package(catkin REQUIRED COMPONENTS
|
||||||
roscpp
|
roscpp
|
||||||
|
rospy
|
||||||
std_msgs
|
std_msgs
|
||||||
std_srvs
|
std_srvs
|
||||||
|
message_generation
|
||||||
)
|
)
|
||||||
|
|
||||||
## System dependencies are found with CMake's conventions
|
## System dependencies are found with CMake's conventions
|
||||||
@@ -47,11 +49,10 @@ find_package(catkin REQUIRED COMPONENTS
|
|||||||
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
|
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
|
||||||
|
|
||||||
## Generate messages in the 'msg' folder
|
## Generate messages in the 'msg' folder
|
||||||
# add_message_files(
|
add_message_files(
|
||||||
# FILES
|
FILES
|
||||||
# Message1.msg
|
Bytes.msg
|
||||||
# Message2.msg
|
)
|
||||||
# )
|
|
||||||
|
|
||||||
## Generate services in the 'srv' folder
|
## Generate services in the 'srv' folder
|
||||||
# add_service_files(
|
# add_service_files(
|
||||||
@@ -68,10 +69,10 @@ find_package(catkin REQUIRED COMPONENTS
|
|||||||
# )
|
# )
|
||||||
|
|
||||||
## Generate added messages and services with any dependencies listed here
|
## Generate added messages and services with any dependencies listed here
|
||||||
# generate_messages(
|
generate_messages(
|
||||||
# DEPENDENCIES
|
DEPENDENCIES
|
||||||
# std_msgs
|
std_msgs
|
||||||
# )
|
)
|
||||||
|
|
||||||
################################################
|
################################################
|
||||||
## Declare ROS dynamic reconfigure parameters ##
|
## Declare ROS dynamic reconfigure parameters ##
|
||||||
@@ -103,9 +104,9 @@ find_package(catkin REQUIRED COMPONENTS
|
|||||||
## CATKIN_DEPENDS: catkin_packages dependent projects also need
|
## CATKIN_DEPENDS: catkin_packages dependent projects also need
|
||||||
## DEPENDS: system dependencies of this project that dependent projects also need
|
## DEPENDS: system dependencies of this project that dependent projects also need
|
||||||
catkin_package(
|
catkin_package(
|
||||||
# INCLUDE_DIRS include
|
INCLUDE_DIRS include
|
||||||
# LIBRARIES test_topic
|
# LIBRARIES test_topic
|
||||||
# CATKIN_DEPENDS roscpp std_msgs
|
CATKIN_DEPENDS roscpp rospy message_runtime
|
||||||
# DEPENDS system_lib
|
# DEPENDS system_lib
|
||||||
)
|
)
|
||||||
|
|
||||||
|
@@ -13,15 +13,15 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
#include <ros/ros.h>
|
#include <ros/ros.h>
|
||||||
#include <std_msgs/String.h>
|
|
||||||
#include <std_srvs/Empty.h>
|
#include <std_srvs/Empty.h>
|
||||||
#include <vector>
|
#include <vector>
|
||||||
#include <thread>
|
#include <thread>
|
||||||
|
#include "test_topic/Bytes.h"
|
||||||
|
|
||||||
namespace xyfc_std
|
namespace xyfc_std
|
||||||
{
|
{
|
||||||
|
|
||||||
using MsgType = std_msgs::String;
|
using MsgType = test_topic::Bytes;
|
||||||
using ThreadFuncType = boost::function<void (void)>;
|
using ThreadFuncType = boost::function<void (void)>;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
4
src/test_topic/msg/Bytes.msg
Normal file
4
src/test_topic/msg/Bytes.msg
Normal file
@@ -0,0 +1,4 @@
|
|||||||
|
uint8[] data
|
||||||
|
time tick
|
||||||
|
int64 length
|
||||||
|
int64 id
|
@@ -50,14 +50,26 @@
|
|||||||
<!-- <doc_depend>doxygen</doc_depend> -->
|
<!-- <doc_depend>doxygen</doc_depend> -->
|
||||||
<buildtool_depend>catkin</buildtool_depend>
|
<buildtool_depend>catkin</buildtool_depend>
|
||||||
<build_depend>roscpp</build_depend>
|
<build_depend>roscpp</build_depend>
|
||||||
|
<build_depend>rospy</build_depend>
|
||||||
<build_depend>std_msgs</build_depend>
|
<build_depend>std_msgs</build_depend>
|
||||||
<build_depend>std_srvs</build_depend>
|
<build_depend>std_srvs</build_depend>
|
||||||
<build_export_depend>roscpp</build_export_depend>
|
<build_export_depend>roscpp</build_export_depend>
|
||||||
|
<build_export_depend>rospy</build_export_depend>
|
||||||
<build_export_depend>std_msgs</build_export_depend>
|
<build_export_depend>std_msgs</build_export_depend>
|
||||||
<exec_depend>roscpp</exec_depend>
|
<exec_depend>roscpp</exec_depend>
|
||||||
|
<exec_depend>rospy</exec_depend>
|
||||||
<exec_depend>std_msgs</exec_depend>
|
<exec_depend>std_msgs</exec_depend>
|
||||||
<exec_depend>std_srvs</exec_depend>
|
<exec_depend>std_srvs</exec_depend>
|
||||||
|
|
||||||
|
<build_depend>message_generation</build_depend>
|
||||||
|
<build_depend>message_runtime</build_depend>
|
||||||
|
|
||||||
|
<build_export_depend>message_generation</build_export_depend>
|
||||||
|
<build_export_depend>message_runtime</build_export_depend>
|
||||||
|
|
||||||
|
<exec_depend>message_generation</exec_depend>
|
||||||
|
<exec_depend>message_runtime</exec_depend>
|
||||||
|
|
||||||
|
|
||||||
<!-- The export tag contains other, unspecified, tags -->
|
<!-- The export tag contains other, unspecified, tags -->
|
||||||
<export>
|
<export>
|
||||||
|
@@ -32,8 +32,9 @@ MinSubscriber::~MinSubscriber()
|
|||||||
|
|
||||||
void MinSubscriber::callback(const boost::shared_ptr<MsgType const> &msg)
|
void MinSubscriber::callback(const boost::shared_ptr<MsgType const> &msg)
|
||||||
{
|
{
|
||||||
ROS_INFO("I heard: [%s]", msg->data.c_str());
|
ROS_INFO("I heard: [%s]", &msg->data[0]);
|
||||||
_serial.send(msg->data.c_str(), strlen(msg->data.c_str()));
|
|
||||||
|
_serial.send((const char *)&msg->data[0], msg->length);
|
||||||
}
|
}
|
||||||
|
|
||||||
int main(int argc, char *argv[])
|
int main(int argc, char *argv[])
|
||||||
|
@@ -17,14 +17,13 @@ protected:
|
|||||||
|
|
||||||
void testMinHandler::callback(const boost::shared_ptr<MsgType const> &msg)
|
void testMinHandler::callback(const boost::shared_ptr<MsgType const> &msg)
|
||||||
{
|
{
|
||||||
std::stringstream ss;
|
ROS_INFO("handle :%s", &msg->data[0]);
|
||||||
|
|
||||||
ss << "handled data: " << msg->data;
|
|
||||||
ROS_INFO("handle :%s", msg->data.c_str());
|
|
||||||
std::this_thread::sleep_for(std::chrono::seconds(2));
|
std::this_thread::sleep_for(std::chrono::seconds(2));
|
||||||
|
std::string str = "handled :";
|
||||||
|
str.append((const char *)&msg->data[0]);
|
||||||
|
|
||||||
MsgType send;
|
MsgType send;
|
||||||
send.data = ss.str();
|
send.data.assign(str.begin(), str.end());
|
||||||
_pub.publish(send);
|
_pub.publish(send);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@@ -1,7 +1,7 @@
|
|||||||
#include <ros/ros.h>
|
#include <ros/ros.h>
|
||||||
#include <std_msgs/String.h>
|
#include "test_topic/Bytes.h"
|
||||||
|
|
||||||
using MsgType = std_msgs::String;
|
using MsgType = test_topic::Bytes;
|
||||||
class TimerPublisher: ros::NodeHandle {
|
class TimerPublisher: ros::NodeHandle {
|
||||||
public:
|
public:
|
||||||
TimerPublisher();
|
TimerPublisher();
|
||||||
@@ -29,13 +29,19 @@ void TimerPublisher::run()
|
|||||||
ros::Rate loop_rate(10);
|
ros::Rate loop_rate(10);
|
||||||
while (ros::ok())
|
while (ros::ok())
|
||||||
{
|
{
|
||||||
std_msgs::String msg;
|
test_topic::Bytes msg;
|
||||||
|
|
||||||
std::stringstream ss;
|
std::stringstream ss;
|
||||||
ss << "hello world " << _count++ << "\n";
|
ss << "hello world " << _count++ << "\n";
|
||||||
msg.data = ss.str();
|
auto str = ss.str();
|
||||||
|
|
||||||
ROS_INFO("%s", msg.data.c_str());
|
msg.data.assign(str.begin(), str.end());
|
||||||
|
msg.data.push_back(0);
|
||||||
|
msg.id = 1,
|
||||||
|
msg.length = str.size() + 1;
|
||||||
|
msg.tick = ros::Time::now();
|
||||||
|
|
||||||
|
ROS_INFO("%s", str.c_str());
|
||||||
_sender.publish(msg);
|
_sender.publish(msg);
|
||||||
|
|
||||||
ros::spinOnce();
|
ros::spinOnce();
|
||||||
|
Reference in New Issue
Block a user