39 #include <std_msgs/Bool.h> 40 #include <geometry_msgs/TwistStamped.h> 41 #include <can_msgs/Frame.h> 42 #include <dataspeed_ulc_msgs/UlcCmd.h> 43 #include <dataspeed_ulc_msgs/UlcReport.h> 54 void recvCan(
const can_msgs::FrameConstPtr& msg);
55 void recvUlcCmd(
const dataspeed_ulc_msgs::UlcCmdConstPtr& msg);
57 void recvTwist(
const geometry_msgs::TwistConstPtr& msg);
59 void recvEnable(
const std_msgs::BoolConstPtr& msg);
ros::Subscriber sub_twist_stamped_
void recvEnable(const std_msgs::BoolConstPtr &msg)
void recvTwistCmd(const geometry_msgs::Twist &msg)
void sendCmdMsg(bool cfg)
void recvCan(const can_msgs::FrameConstPtr &msg)
dataspeed_ulc_msgs::UlcCmd ulc_cmd_
void recvTwist(const geometry_msgs::TwistConstPtr &msg)
UlcNode(ros::NodeHandle &n, ros::NodeHandle &pn)
void recvTwistStamped(const geometry_msgs::TwistStampedConstPtr &msg)
ros::Subscriber sub_enable_
ros::Publisher pub_report_
ros::Subscriber sub_twist_
void recvUlcCmd(const dataspeed_ulc_msgs::UlcCmdConstPtr &msg)
void configTimerCb(const ros::TimerEvent &event)