34 #include <xpp_msgs/RobotStateCartesian.h>    44   xpp_msgs::RobotStateJoint joint_msg;
    45   joint_msg.base = msg.base;
    46   joint_state_pub.
publish(joint_msg);
    50 int main(
int argc, 
char *argv[])
    52   ::ros::init(argc, argv, 
"quadrotor_urdf_visualizer");
    55   const std::string joint_quadrotor = 
"xpp/joint_quadrotor_des";
    57   joint_state_pub = n.
advertise<xpp_msgs::RobotStateJoint>(joint_quadrotor, 1);
    60   std::string 
urdf = 
"quadrotor_rviz_urdf_robot_description";
    61   UrdfVisualizer node_des(urdf, {}, 
"base", 
"world", joint_quadrotor, 
"quadrotor");
 void publish(const boost::shared_ptr< M > &message) const 
static const std::string robot_state_desired("/xpp/state_des")
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
int main(int argc, char *argv[])
ros::Publisher joint_state_pub
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void StateCallback(const xpp_msgs::RobotStateCartesian &msg)