ROS message callback function
My code subscribes to a customized rosmsg "/lcm_to_ros/leg_corol_data" by doing ros::Subscriber sub = n.subscribe("/lcm_to_ros/leg_corol_data", 1000, legCallback);
This Rosmsg has a type of "leg_control_data_lcmt"
How to write the correct callback function? callback function works for msg type"std_msgs/String.h", but not for the class "leg_control_data_lcmt" I created.
The callback function fails because of the rosmsg type "leg_control_data_lcmt" imported from "leg_control_data_lcmt.hpp". I wonder how to handle customized rosmsg in callback function??
void legCallback(const leg_control_data_lcmt* msg)
{
ROS_INFO("test");
}
The error is like this. Is it because I did not include callback function in Cmakefile. How can I do this ?
In file included from /opt/ros/kinetic/include/ros/serialization.h:37:0,
from /opt/ros/kinetic/include/ros/publisher.h:34,
from /opt/ros/kinetic/include/ros/node_handle.h:32,
from /opt/ros/kinetic/include/ros/ros.h:45,
from /home/chao/catkin_ws/src/new_joint_pub/src/state_publisher.cpp:2:
/opt/ros/kinetic/include/ros/message_traits.h: In instantiation of ‘static const char* ros::message_traits::MD5Sum<M>::value() [with M = leg_control_data_lcmt]’:
/opt/ros/kinetic/include/ros/message_traits.h:228:102: required from ‘const char* ros::message_traits::md5sum() [with M = leg_control_data_lcmt]’
/opt/ros/kinetic/include/ros/subscribe_options.h:89:49: required from ‘void ros::SubscribeOptions::initByFullCallbackType(const string&, uint32_t, const boost::function<void(P)>&, const boost::function<boost::shared_ptr<typename ros::ParameterAdapter<P>::Message>()>&) [with P = const leg_control_data_lcmt&; std::__cxx11::string = std::__cxx11::basic_string<char>; uint32_t = unsigned int; typename ros::ParameterAdapter<P>::Message = leg_control_data_lcmt]’
/opt/ros/kinetic/include/ros/node_handle.h:406:5: required from ‘ros::Subscriber ros::NodeHandle::subscribe(const string&, uint32_t, void (T::*)(M), T*, const ros::TransportHints&) [with M = const leg_control_data_lcmt&; T = SubscribeAndPublish; std::__cxx11::string = std::__cxx11::basic_string<char>; uint32_t = unsigned int]’
/home/chao/catkin_ws/src/new_joint_pub/src/state_publisher.cpp:17:94: required from here
/opt/ros/kinetic/include/ros/message_traits.h:121:28: error: ‘__s_getMD5Sum’ is not a member of ‘leg_control_data_lcmt’
return M::__s_getMD5Sum().c_str();
^
/opt/ros/kinetic/include/ros/message_traits.h: In instantiation of ‘static const char* ros::message_traits::DataType<M>::value() [with M = leg_control_data_lcmt]’:
/opt/ros/kinetic/include/ros/message_traits.h:237:104: required from ‘const char* ros::message_traits::datatype() [with M = leg_control_data_lcmt]’
/opt/ros/kinetic/include/ros/subscribe_options.h:90:53: required from ‘void ros::SubscribeOptions::initByFullCallbackType(const string&, uint32_t, const boost::function<void(P)>&, const boost::function<boost::shared_ptr<typename ros::ParameterAdapter<P>::Message>()>&) [with P = const leg_control_data_lcmt&; std::__cxx11::string = std::__cxx11::basic_string<char>; uint32_t = unsigned int; typename ros::ParameterAdapter<P>::Message = leg_control_data_lcmt]’
/opt/ros/kinetic/include/ros/node_handle.h:406:5: required from ‘ros::Subscriber ros::NodeHandle::subscribe(const string&, uint32_t, void (T::*)(M), T*, const ros::TransportHints&) [with M = const leg_control_data_lcmt&; T = SubscribeAndPublish; std::__cxx11::string = std::__cxx11::basic_string<char>; uint32_t = unsigned int]’
/home/chao/catkin_ws/src/new_joint_pub/src/state_publisher.cpp:17:94: required from here
/opt/ros/kinetic/include/ros/message_traits.h:138:30: error: ‘__s_getDataType’ is not a member of ‘leg_control_data_lcmt’
return M::__s_getDataType().c_str();
^
In file included from /opt/ros/kinetic/include/ros/publisher.h:34:0,
from /opt/ros/kinetic/include/ros/node_handle.h ...