joint_trajectory_action_controller.cpp
Go to the documentation of this file.
1 
29 #include <std_msgs/Float64.h>
30 #include <boost/algorithm/string.hpp>
31 #include <string>
32 #include <vector>
33 
34 namespace shadowrobot
35 {
37  {
39  new JTAS("/r_arm_controller/joint_trajectory_action",
41  false));
42 
43  // Create a map of joint names to their command publishers
44  // Hand joints
45  // @todo this could be read from the controller manager
46  // rosservice call /controller_manager/list_controllers
47  std::string hand_names[] =
48  {
49  "ffj0", "ffj3", "ffj4",
50  "lfj0", "lfj3", "lfj4", "lfj5",
51  "mfj0", "mfj3", "mfj4",
52  "rfj0", "rfj3", "rfj4",
53  "thj1", "thj2", "thj3", "thj4", "thj5",
54  "wrj1", "wrj2"
55  };
56  for (size_t i = 0; i < 20; i++)
57  {
58  joint_pub[hand_names[i]] = nh.advertise<std_msgs::Float64>(
59  "/sh_" + hand_names[i] + "_mixed_position_velocity_controller/command", 2);
60 
61  joint_pub[boost::to_upper_copy(hand_names[i])] = nh.advertise<std_msgs::Float64>(
62  "/sh_" + hand_names[i] + "_mixed_position_velocity_controller/command", 2);
63  }
64 
65  // Arm joints
66  std::string arm_names[] = {"sr", "ss", "es", "er"};
67  for (size_t i = 0; i < 4; i++)
68  {
69  joint_pub[arm_names[i]] = nh.advertise<std_msgs::Float64>(
70  "/sa_" + arm_names[i] + "_position_controller/command", 2);
71  }
72 
73  // Arm joints: 2 naming conventions
74  std::string arm_names_2[] = {"ShoulderJRotate", "ShoulderJSwing", "ElbowJSwing", "ElbowJRotate"};
75  for (size_t i = 0; i < 4; i++)
76  {
77  joint_pub[arm_names_2[i]] = nh.advertise<std_msgs::Float64>(
78  "/sa_" + arm_names[i] + "_position_controller/command", 2);
79  }
80 
81  ROS_DEBUG("Starting JointTrajectoryActionController server");
82  action_server->start();
83  }
84 
86  const control_msgs::FollowJointTrajectoryGoalConstPtr &goal
87  )
88  {
89  bool success = true;
90  std::vector<std::string> joint_names = goal->trajectory.joint_names;
91  JointTrajectoryPointVec trajectory_points = goal->trajectory.points;
92  trajectory_msgs::JointTrajectoryPoint trajectory_step;
93 
94  // @todo We should probably be looking at goal->trajectory.header.stamp to
95  // work out what time to start the action.
96  // std::cout << goal->trajectory.header.stamp << " - " << ros::Time::now() << std::endl;
97 
98  // loop through the steps
99  ros::Duration sleeping_time(0.0), last_time(0.0);
100  for (size_t index_step = 0; index_step < trajectory_points.size(); ++index_step)
101  {
102  trajectory_step = trajectory_points[index_step];
103 
104  // check if preempted (cancelled), bail out if we are
105  if (action_server->isPreemptRequested() || !ros::ok())
106  {
107  ROS_INFO("Joint Trajectory Action Preempted");
108  action_server->setPreempted();
109  success = false;
110  break;
111  }
112 
113  // send out the positions for this step to the joints
114  for (size_t i = 0; i < joint_names.size(); i++)
115  {
116  ROS_DEBUG_STREAM("trajectory: " << joint_names[i] << " " << trajectory_step.positions[i] << " / sleep: " <<
117  sleeping_time.toSec());
118  ros::Publisher pub = joint_pub[joint_names[i]];
119  std_msgs::Float64 msg;
120  msg.data = trajectory_step.positions[i];
121  pub.publish(msg);
122  }
123  // Wait until this step is supposed to be completed.
124  // @todo This assumes that the movement will be instant! We should really
125  // be working out how long the movement will take?
126  sleeping_time = trajectory_step.time_from_start - last_time;
127  sleeping_time.sleep();
128  last_time = trajectory_step.time_from_start;
129  }
130 
131  // send the result back
132  control_msgs::FollowJointTrajectoryResult joint_trajectory_result;
133  if (success)
134  {
135  action_server->setSucceeded(joint_trajectory_result);
136  }
137  else
138  {
139  action_server->setAborted(joint_trajectory_result);
140  }
141  }
142 } // namespace shadowrobot
143 
144 
145 int main(int argc, char **argv)
146 {
147  ros::init(argc, argv, "sr_joint_trajectory_action_controller");
148 
149  ros::AsyncSpinner spinner(1); // Use 1 thread
150  spinner.start();
152  ros::spin();
153  // ros::waitForShutdown();
154 
155  return 0;
156 }
157 
158 
159 /* For the emacs weenies in the crowd.
160 Local Variables:
161  c-basic-offset: 2
162 End:
163 */
164 // vim: sw=2:ts=2
std::vector< trajectory_msgs::JointTrajectoryPoint > JointTrajectoryPointVec
list joint_names
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
actionlib::SimpleActionServer< control_msgs::FollowJointTrajectoryAction > JTAS
void spinner()
ROSCPP_DECL void spin(Spinner &spinner)
Implement an actionlib server to execute a control_msgs::JointTrajectoryAction. Follows the given tra...
#define ROS_INFO(...)
int main(int argc, char **argv)
ROSCPP_DECL bool ok()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_DEBUG_STREAM(args)
void execute_trajectory(const control_msgs::FollowJointTrajectoryGoalConstPtr &goal)
#define ROS_DEBUG(...)


sr_mechanism_controllers
Author(s): Ugo Cupcic
autogenerated on Tue Oct 13 2020 03:55:58