40 #include <sensor_msgs/JointState.h>
41 #include <boost/thread.hpp>
51 ss <<
"Fake controller '" <<
name <<
"' with joints [ ";
52 std::copy(joints.begin(), joints.end(), std::ostream_iterator<std::string>(ss,
" "));
69 : BaseFakeController(
name, joints, pub)
77 ROS_INFO(
"Fake execution of trajectory");
78 if (
t.joint_trajectory.points.empty())
81 sensor_msgs::JointState js;
82 const trajectory_msgs::JointTrajectoryPoint& last =
t.joint_trajectory.points.back();
83 js.header =
t.joint_trajectory.header;
85 js.name =
t.joint_trajectory.joint_names;
86 js.position = last.positions;
87 js.velocity = last.velocities;
88 js.effort = last.effort;
134 ROS_INFO(
"Fake trajectory execution cancelled");
161 ROS_INFO(
"Fake execution of trajectory");
162 sensor_msgs::JointState js;
163 js.header =
t.joint_trajectory.header;
164 js.name =
t.joint_trajectory.joint_names;
169 for (std::vector<trajectory_msgs::JointTrajectoryPoint>::const_iterator via =
t.joint_trajectory.points.begin(),
170 end =
t.joint_trajectory.points.end();
173 js.position = via->positions;
174 js.velocity = via->velocities;
175 js.effort = via->effort;
178 if (wait_time.
toSec() > std::numeric_limits<float>::epsilon())
180 ROS_DEBUG(
"Fake execution: waiting %0.1fs for next via point, %ld remaining", wait_time.
toSec(), end - via);
186 ROS_DEBUG(
"Fake execution of trajectory: done");
191 : ThreadedController(
name, joints, pub), rate_(10)
202 void interpolate(sensor_msgs::JointState& js,
const trajectory_msgs::JointTrajectoryPoint& prev,
203 const trajectory_msgs::JointTrajectoryPoint& next,
const ros::Duration& elapsed)
207 if (
duration > std::numeric_limits<double>::epsilon())
208 alpha = (elapsed -
prev.time_from_start).toSec() /
duration;
210 js.position.resize(
prev.positions.size());
211 for (std::size_t i = 0, end =
prev.positions.size(); i < end; ++i)
213 js.position[i] =
prev.positions[i] + alpha * (
next.positions[i] -
prev.positions[i]);
220 ROS_INFO(
"Fake execution of trajectory");
221 if (
t.joint_trajectory.points.empty())
224 sensor_msgs::JointState js;
225 js.header =
t.joint_trajectory.header;
226 js.name =
t.joint_trajectory.joint_names;
228 const std::vector<trajectory_msgs::JointTrajectoryPoint>& points =
t.joint_trajectory.points;
229 std::vector<trajectory_msgs::JointTrajectoryPoint>::const_iterator
prev = points.begin(),
230 next = points.begin() + 1,
238 while (next != end && elapsed >
next->time_from_start)
247 ROS_DEBUG(
"elapsed: %.3f via points %td,%td / %td alpha: %.3f", elapsed.
toSec(), prev - points.begin(),
248 next - points.begin(), end - points.begin(),
249 duration > std::numeric_limits<double>::epsilon() ? (elapsed -
prev->time_from_start).toSec() /
duration :
251 interpolate(js, *prev, *next, elapsed);
260 ROS_DEBUG(
"elapsed: %.3f via points %td,%td / %td alpha: 1.0", elapsed.
toSec(), prev - points.begin(),
261 next - points.begin(), end - points.begin());
264 interpolate(js, *prev, *prev,
prev->time_from_start);
268 ROS_DEBUG(
"Fake execution of trajectory: done");