example_03_command_node.cpp
Go to the documentation of this file.
1 #include "ros/ros.h"
2 #include "sensor_msgs/JointState.h"
3 #include "hebiros/AddGroupFromNamesSrv.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_03_command_node");
21  ros::Rate loop_rate(200);
22 
23  std::string group_name = "my_group";
24 
25  //Create a client which uses the service to create a group
26  ros::ServiceClient add_group_client = n.serviceClient<AddGroupFromNamesSrv>(
27  "/hebiros/add_group_from_names");
28 
29  //Create a subscriber to receive feedback from a group
30  //Register feedback_callback as a callback which runs when feedback is received
31  ros::Subscriber feedback_subscriber = n.subscribe(
32  "/hebiros/"+group_name+"/feedback/joint_state", 100, feedback_callback);
33 
34  //Create a publisher to send desired commands to a group
35  ros::Publisher command_publisher = n.advertise<sensor_msgs::JointState>(
36  "/hebiros/"+group_name+"/command/joint_state", 100);
37 
38  AddGroupFromNamesSrv add_group_srv;
39 
40  //Construct a group using 3 known modules
41  add_group_srv.request.group_name = group_name;
42  add_group_srv.request.names = {"base", "shoulder", "elbow"};
43  add_group_srv.request.families = {"HEBI"};
44  //Call the add_group_from_urdf service to create a group until it succeeds
45  //Specific topics and services will now be available under this group's namespace
46  while(!add_group_client.call(add_group_srv)) {}
47 
48  //Construct a JointState to command the modules
49  //This may potentially contain a name, position, velocity, and effort for each module
50  sensor_msgs::JointState command_msg;
51  command_msg.name.push_back("HEBI/base");
52  command_msg.name.push_back("HEBI/shoulder");
53  command_msg.name.push_back("HEBI/elbow");
54 
55  command_msg.effort.resize(3);
56 
57  feedback.position.reserve(3);
58 
59  double spring_constant = -10;
60 
61  while(ros::ok()) {
62 
63  //Apply Hooke's Law: F = -k * x to all modules and publish as a command
64  command_msg.effort[0] = spring_constant * feedback.position[0];
65  command_msg.effort[1] = spring_constant * feedback.position[1];
66  command_msg.effort[2] = spring_constant * feedback.position[2];
67  command_publisher.publish(command_msg);
68 
69  ros::spinOnce();
70  loop_rate.sleep();
71  }
72 
73  return 0;
74 }
75 
76 
77 
78 
79 
80 
81 
82 
83 
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
sensor_msgs::JointState feedback
int main(int argc, char **argv)
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())
void feedback_callback(sensor_msgs::JointState data)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
ROSCPP_DECL bool ok()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool sleep()
ROSCPP_DECL void spinOnce()


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