2 #include "sensor_msgs/JointState.h"     3 #include "hebiros/AddGroupFromURDFSrv.h"    16 int main(
int argc, 
char **argv) {
    19   ros::init(argc, argv, 
"example_moveit_node");
    23   std::string group_name = 
"x_demo";
    28     "/hebiros/add_group_from_urdf");
    37     "/hebiros/"+group_name+
"/command/joint_state", 100);
    39   AddGroupFromURDFSrv add_group_srv;
    42   add_group_srv.request.group_name = group_name;
    45   while(!add_group_client.
call(add_group_srv)) {}
 ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
 
void publish(const boost::shared_ptr< M > &message) const 
 
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
 
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
 
bool call(MReq &req, MRes &res)
 
sensor_msgs::JointState feedback
 
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
 
void feedback_callback(sensor_msgs::JointState data)
 
ROSCPP_DECL void spinOnce()
 
int main(int argc, char **argv)