example_02_feedback_node.cpp
Go to the documentation of this file.
1 #include "ros/ros.h"
2 #include "hebiros/FeedbackMsg.h"
3 #include "hebiros/AddGroupFromNamesSrv.h"
4 #include "hebiros/SizeSrv.h"
5 
6 using namespace hebiros;
7 
8 
9 //Global variable and callback function used to store feedback data
10 FeedbackMsg feedback;
11 
12 void feedback_callback(FeedbackMsg data) {
13  feedback = data;
14 }
15 
16 
17 int main(int argc, char **argv) {
18 
19  //Initialize ROS node
20  ros::init(argc, argv, "example_02_feedback_node");
22  ros::Rate loop_rate(200);
23 
24  std::string group_name = "my_group";
25 
26  //Create a client which uses the service to create a group
27  ros::ServiceClient add_group_client = n.serviceClient<AddGroupFromNamesSrv>(
28  "/hebiros/add_group_from_names");
29 
30  //Create a client which uses the service to find the size of a group
31  ros::ServiceClient size_client = n.serviceClient<SizeSrv>(
32  "/hebiros/"+group_name+"/size");
33 
34  //Create a subscriber to receive feedback from a group
35  //Register feedback_callback as a callback which runs when feedback is received
36  ros::Subscriber feedback_subscriber = n.subscribe(
37  "/hebiros/"+group_name+"/feedback", 100, feedback_callback);
38 
39  AddGroupFromNamesSrv add_group_srv;
40  SizeSrv size_srv;
41 
42  //Construct a group using 3 known modules
43  add_group_srv.request.group_name = group_name;
44  add_group_srv.request.names = {"base", "shoulder", "elbow"};
45  add_group_srv.request.families = {"HEBI"};
46  //Call the add_group_from_urdf service to create a group until it succeeds
47  //Specific topics and services will now be available under this group's namespace
48  while(!add_group_client.call(add_group_srv)) {}
49 
50  //Call the size service for the newly created group
51  size_client.call(size_srv);
52 
53  feedback.accelerometer.reserve(size_srv.response.size);
54  feedback.gyro.reserve(size_srv.response.size);
55 
56  while(ros::ok()) {
57 
58  //Display IMU data for each module
59  //You can also see feedback by running "rostopic echo /hebiros/<group>/feedback"
60  for (int i = 0; i < size_srv.response.size; i++) {
61  std::cout << "Module " << i << ": " << std::endl;
62  std::cout << "Accelerometer: " <<
63  feedback.accelerometer[i].x << ", " <<
64  feedback.accelerometer[i].y << ", " <<
65  feedback.accelerometer[i].z << std::endl;
66  std::cout << "Gyro: " <<
67  feedback.gyro[i].x << ", " <<
68  feedback.gyro[i].y << ", " <<
69  feedback.gyro[i].z << std::endl;
70  }
71  std::cout << std::endl;
72 
73  ros::spinOnce();
74  loop_rate.sleep();
75  }
76 
77  return 0;
78 }
79 
80 
81 
82 
83 
84 
85 
86 
87 
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
FeedbackMsg feedback
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)
void feedback_callback(FeedbackMsg data)
ROSCPP_DECL bool ok()
bool sleep()
ROSCPP_DECL void spinOnce()
int main(int argc, char **argv)


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