2 #include "hebiros/FeedbackMsg.h" 3 #include "hebiros/AddGroupFromNamesSrv.h" 4 #include "hebiros/SizeSrv.h" 17 int main(
int argc,
char **argv) {
20 ros::init(argc, argv,
"example_02_feedback_node");
24 std::string group_name =
"my_group";
28 "/hebiros/add_group_from_names");
32 "/hebiros/"+group_name+
"/size");
39 AddGroupFromNamesSrv add_group_srv;
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"};
48 while(!add_group_client.
call(add_group_srv)) {}
51 size_client.call(size_srv);
53 feedback.accelerometer.reserve(size_srv.response.size);
54 feedback.gyro.reserve(size_srv.response.size);
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: " <<
71 std::cout << std::endl;
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
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 void spinOnce()
int main(int argc, char **argv)