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,
" "));
79 ROS_INFO(
"Fake execution of trajectory");
80 if (t.joint_trajectory.points.empty())
83 sensor_msgs::JointState js;
84 const trajectory_msgs::JointTrajectoryPoint& last = t.joint_trajectory.points.back();
85 js.header = t.joint_trajectory.header;
87 js.name = t.joint_trajectory.joint_names;
88 js.position = last.positions;
89 js.velocity = last.velocities;
90 js.effort = last.effort;
136 ROS_INFO(
"Fake trajectory execution cancelled");
165 ROS_INFO(
"Fake execution of trajectory");
166 sensor_msgs::JointState js;
167 js.header = t.joint_trajectory.header;
168 js.name = t.joint_trajectory.joint_names;
173 for (std::vector<trajectory_msgs::JointTrajectoryPoint>::const_iterator via = t.joint_trajectory.points.begin(),
174 end = t.joint_trajectory.points.end();
177 js.position = via->positions;
178 js.velocity = via->velocities;
179 js.effort = via->effort;
182 if (waitTime.
toSec() > std::numeric_limits<float>::epsilon())
184 ROS_DEBUG(
"Fake execution: waiting %0.1fs for next via point, %ld remaining", waitTime.
toSec(), end - via);
190 ROS_DEBUG(
"Fake execution of trajectory: done");
208 void interpolate(sensor_msgs::JointState& js,
const trajectory_msgs::JointTrajectoryPoint& prev,
209 const trajectory_msgs::JointTrajectoryPoint& next,
const ros::Duration& elapsed)
211 double duration = (next.time_from_start - prev.time_from_start).toSec();
213 if (duration > std::numeric_limits<double>::epsilon())
214 alpha = (elapsed - prev.time_from_start).toSec() / duration;
216 js.position.resize(prev.positions.size());
217 for (std::size_t i = 0, end = prev.positions.size(); i < end; ++i)
219 js.position[i] = prev.positions[i] + alpha * (next.positions[i] - prev.positions[i]);
226 ROS_INFO(
"Fake execution of trajectory");
227 if (t.joint_trajectory.points.empty())
230 sensor_msgs::JointState js;
231 js.header = t.joint_trajectory.header;
232 js.name = t.joint_trajectory.joint_names;
234 const std::vector<trajectory_msgs::JointTrajectoryPoint>& points = t.joint_trajectory.points;
235 std::vector<trajectory_msgs::JointTrajectoryPoint>::const_iterator prev = points.begin(),
236 next = points.begin() + 1,
244 while (next != end && elapsed > next->time_from_start)
252 double duration = (next->time_from_start - prev->time_from_start).toSec();
253 ROS_DEBUG(
"elapsed: %.3f via points %td,%td / %td alpha: %.3f", elapsed.
toSec(), prev - points.begin(),
254 next - points.begin(), end - points.begin(),
255 duration > std::numeric_limits<double>::epsilon() ? (elapsed - prev->time_from_start).toSec() / duration :
257 interpolate(js, *prev, *next, elapsed);
266 ROS_DEBUG(
"elapsed: %.3f via points %td,%td / %td alpha: 1.0", elapsed.
toSec(), prev - points.begin(),
267 next - points.begin(), end - points.begin());
270 interpolate(js, *prev, *prev, prev->time_from_start);
274 ROS_DEBUG(
"Fake execution of trajectory: done");
void publish(const boost::shared_ptr< M > &message) const
BaseFakeController(const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub)
virtual bool waitForExecution(const ros::Duration &)
virtual moveit_controller_manager::ExecutionStatus getLastExecutionStatus()
ViaPointController(const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub)
virtual void execTrajectory(const moveit_msgs::RobotTrajectory &t)=0
virtual bool sendTrajectory(const moveit_msgs::RobotTrajectory &t)
void getJoints(std::vector< std::string > &joints) const
virtual bool sendTrajectory(const moveit_msgs::RobotTrajectory &t)
virtual bool waitForExecution(const ros::Duration &)
std::vector< std::string > joints_
~InterpolatingController()
ThreadedController(const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub)
virtual bool cancelExecution()
const ros::Publisher & pub_
ROSCPP_DECL bool get(const std::string &key, std::string &s)
virtual void execTrajectory(const moveit_msgs::RobotTrajectory &t)
LastPointController(const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub)
virtual moveit_controller_manager::ExecutionStatus getLastExecutionStatus()
moveit_controller_manager::ExecutionStatus status_
#define ROS_INFO_STREAM(args)
virtual bool cancelExecution()
InterpolatingController(const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub)
virtual void execTrajectory(const moveit_msgs::RobotTrajectory &t)
virtual void cancelTrajectory()