example_moveit_node.cpp
Go to the documentation of this file.
1 #include "ros/ros.h"
2 #include "sensor_msgs/JointState.h"
3 #include "hebiros/AddGroupFromURDFSrv.h"
4 
5 using namespace hebiros;
6 
7 
8 //Global variable and callback function used to store feedback data
9 sensor_msgs::JointState feedback;
10 
11 void feedback_callback(sensor_msgs::JointState data) {
12  feedback = data;
13 }
14 
15 
16 int main(int argc, char **argv) {
17 
18  //Initialize ROS node
19  ros::init(argc, argv, "example_moveit_node");
21  ros::Rate loop_rate(200);
22 
23  std::string group_name = "x_demo";
24 
25  //Create a client which uses the service to create a group
26  //The urdf for x_demo must have already been set in the robot_description parameter
27  ros::ServiceClient add_group_client = n.serviceClient<AddGroupFromURDFSrv>(
28  "/hebiros/add_group_from_urdf");
29 
30  //Create a subscriber to receive feedback from moveit
31  //Register feedback_callback as a callback which runs when feedback is received
32  ros::Subscriber feedback_subscriber = n.subscribe(
33  "/joint_states", 100, feedback_callback);
34 
35  //Create a publisher to send desired commands to a group
36  ros::Publisher command_publisher = n.advertise<sensor_msgs::JointState>(
37  "/hebiros/"+group_name+"/command/joint_state", 100);
38 
39  AddGroupFromURDFSrv add_group_srv;
40 
41  //Construct a group using a urdf
42  add_group_srv.request.group_name = group_name;
43  //Call the add_group_from_urdf service to create a group until it succeeds
44  //Specific topics and services will now be available under this group's namespace
45  while(!add_group_client.call(add_group_srv)) {}
46 
47  while(ros::ok()) {
48 
49  //Publish the feedback from moveit as a command
50  command_publisher.publish(feedback);
51 
52  ros::spinOnce();
53  loop_rate.sleep();
54  }
55 
56  return 0;
57 }
58 
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())
int n
Definition: key_read.py:85
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
ROSCPP_DECL bool ok()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool sleep()
void feedback_callback(sensor_msgs::JointState data)
ROSCPP_DECL void spinOnce()
int main(int argc, char **argv)


hebiros_advanced_examples
Author(s): Xavier Artache , Matthew Tesch
autogenerated on Thu Sep 3 2020 04:13:22