moveit_fake_controllers.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Ioan A. Sucan
5  * Copyright (c) 2016, Robert Haschke
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the names of the authors nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 /* Author: Ioan Sucan, Robert Haschke */
37 
39 #include <ros/param.h>
40 #include <sensor_msgs/JointState.h>
41 #include <boost/thread.hpp>
42 #include <limits>
43 
45 {
46 BaseFakeController::BaseFakeController(const std::string& name, const std::vector<std::string>& joints,
47  const ros::Publisher& pub)
48  : moveit_controller_manager::MoveItControllerHandle(name), joints_(joints), pub_(pub)
49 {
50  std::stringstream ss;
51  ss << "Fake controller '" << name << "' with joints [ ";
52  std::copy(joints.begin(), joints.end(), std::ostream_iterator<std::string>(ss, " "));
53  ss << "]";
54  ROS_INFO_STREAM(ss.str());
55 }
56 
57 void BaseFakeController::getJoints(std::vector<std::string>& joints) const
58 {
59  joints = joints_;
60 }
61 
63 {
65 }
66 
67 LastPointController::LastPointController(const std::string& name, const std::vector<std::string>& joints,
68  const ros::Publisher& pub)
69  : BaseFakeController(name, joints, pub)
70 {
71 }
72 
74 
75 bool LastPointController::sendTrajectory(const moveit_msgs::RobotTrajectory& t)
76 {
77  ROS_INFO("Fake execution of trajectory");
78  if (t.joint_trajectory.points.empty())
79  return true;
80 
81  sensor_msgs::JointState js;
82  const trajectory_msgs::JointTrajectoryPoint& last = t.joint_trajectory.points.back();
83  js.header = t.joint_trajectory.header;
84  js.header.stamp = ros::Time::now();
85  js.name = t.joint_trajectory.joint_names;
86  js.position = last.positions;
87  js.velocity = last.velocities;
88  js.effort = last.effort;
89  pub_.publish(js);
90 
91  return true;
92 }
93 
95 {
96  return true;
97 }
98 
100 {
101  ros::Duration(0.5).sleep(); // give some time to receive the published JointState
102  return true;
103 }
104 
105 ThreadedController::ThreadedController(const std::string& name, const std::vector<std::string>& joints,
106  const ros::Publisher& pub)
107  : BaseFakeController(name, joints, pub)
108 {
109 }
110 
112 {
114 }
115 
117 {
118  cancel_ = true;
119  thread_.join();
120 }
121 
122 bool ThreadedController::sendTrajectory(const moveit_msgs::RobotTrajectory& t)
123 {
124  cancelTrajectory(); // cancel any previous fake motion
125  cancel_ = false;
127  thread_ = boost::thread([this, t] { execTrajectory(t); });
128  return true;
129 }
130 
132 {
134  ROS_INFO("Fake trajectory execution cancelled");
136  return true;
137 }
138 
140 {
141  thread_.join();
143  return true;
144 }
145 
147 {
148  return status_;
149 }
150 
151 ViaPointController::ViaPointController(const std::string& name, const std::vector<std::string>& joints,
152  const ros::Publisher& pub)
153  : ThreadedController(name, joints, pub)
154 {
155 }
156 
158 
159 void ViaPointController::execTrajectory(const moveit_msgs::RobotTrajectory& t)
160 {
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;
165 
166  // publish joint states for all intermediate via points of the trajectory
167  // no further interpolation
168  ros::Time start_time = ros::Time::now();
169  for (std::vector<trajectory_msgs::JointTrajectoryPoint>::const_iterator via = t.joint_trajectory.points.begin(),
170  end = t.joint_trajectory.points.end();
171  !cancelled() && via != end; ++via)
172  {
173  js.position = via->positions;
174  js.velocity = via->velocities;
175  js.effort = via->effort;
176 
177  ros::Duration wait_time = via->time_from_start - (ros::Time::now() - start_time);
178  if (wait_time.toSec() > std::numeric_limits<float>::epsilon())
179  {
180  ROS_DEBUG("Fake execution: waiting %0.1fs for next via point, %ld remaining", wait_time.toSec(), end - via);
181  wait_time.sleep();
182  }
183  js.header.stamp = ros::Time::now();
185  }
186  ROS_DEBUG("Fake execution of trajectory: done");
187 }
188 
189 InterpolatingController::InterpolatingController(const std::string& name, const std::vector<std::string>& joints,
190  const ros::Publisher& pub)
191  : ThreadedController(name, joints, pub), rate_(10)
192 {
193  double r;
194  if (ros::param::get("~fake_interpolating_controller_rate", r))
195  rate_ = ros::WallRate(r);
196 }
197 
199 
200 namespace
201 {
202 void interpolate(sensor_msgs::JointState& js, const trajectory_msgs::JointTrajectoryPoint& prev,
203  const trajectory_msgs::JointTrajectoryPoint& next, const ros::Duration& elapsed)
204 {
205  double duration = (next.time_from_start - prev.time_from_start).toSec();
206  double alpha = 1.0;
207  if (duration > std::numeric_limits<double>::epsilon())
208  alpha = (elapsed - prev.time_from_start).toSec() / duration;
209 
210  js.position.resize(prev.positions.size());
211  for (std::size_t i = 0, end = prev.positions.size(); i < end; ++i)
212  {
213  js.position[i] = prev.positions[i] + alpha * (next.positions[i] - prev.positions[i]);
214  }
215 }
216 } // namespace
217 
218 void InterpolatingController::execTrajectory(const moveit_msgs::RobotTrajectory& t)
219 {
220  ROS_INFO("Fake execution of trajectory");
221  if (t.joint_trajectory.points.empty())
222  return;
223 
224  sensor_msgs::JointState js;
225  js.header = t.joint_trajectory.header;
226  js.name = t.joint_trajectory.joint_names;
227 
228  const std::vector<trajectory_msgs::JointTrajectoryPoint>& points = t.joint_trajectory.points;
229  std::vector<trajectory_msgs::JointTrajectoryPoint>::const_iterator prev = points.begin(), // previous via point
230  next = points.begin() + 1, // currently targetted via point
231  end = points.end();
232 
233  ros::Time start_time = ros::Time::now();
234  while (!cancelled())
235  {
236  ros::Duration elapsed = ros::Time::now() - start_time;
237  // hop to next targetted via point
238  while (next != end && elapsed > next->time_from_start)
239  {
240  ++prev;
241  ++next;
242  }
243  if (next == end)
244  break;
245 
246  double duration = (next->time_from_start - prev->time_from_start).toSec();
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 :
250  1.0);
251  interpolate(js, *prev, *next, elapsed);
252  js.header.stamp = ros::Time::now();
253  pub_.publish(js);
254  rate_.sleep();
255  }
256  if (cancelled())
257  return;
258 
259  ros::Duration elapsed = ros::Time::now() - start_time;
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());
262 
263  // publish last point
264  interpolate(js, *prev, *prev, prev->time_from_start);
265  js.header.stamp = ros::Time::now();
266  pub_.publish(js);
267 
268  ROS_DEBUG("Fake execution of trajectory: done");
269 }
270 
271 } // end namespace moveit_fake_controller_manager
moveit_controller_manager
moveit_fake_controller_manager::LastPointController::sendTrajectory
bool sendTrajectory(const moveit_msgs::RobotTrajectory &t) override
Definition: moveit_fake_controllers.cpp:108
ros::Publisher
moveit_fake_controller_manager::InterpolatingController::rate_
ros::WallRate rate_
Definition: moveit_fake_controllers.h:156
duration
std::chrono::system_clock::duration duration
moveit_fake_controller_manager::LastPointController::cancelExecution
bool cancelExecution() override
Definition: moveit_fake_controllers.cpp:127
moveit_fake_controller_manager::LastPointController::LastPointController
LastPointController(const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub)
Definition: moveit_fake_controllers.cpp:100
moveit_fake_controller_manager::BaseFakeController::joints_
std::vector< std::string > joints_
Definition: moveit_fake_controllers.h:94
moveit_controller_manager::ExecutionStatus::PREEMPTED
PREEMPTED
ros::param::get
ROSCPP_DECL bool get(const std::string &key, bool &b)
moveit_fake_controller_manager::ViaPointController::~ViaPointController
~ViaPointController() override
moveit_controller_manager::ExecutionStatus::ABORTED
ABORTED
moveit_fake_controller_manager::BaseFakeController
Definition: moveit_fake_controllers.h:85
moveit_fake_controller_manager::LastPointController::~LastPointController
~LastPointController() override
moveit_fake_controller_manager::ThreadedController::execTrajectory
virtual void execTrajectory(const moveit_msgs::RobotTrajectory &t)=0
moveit_fake_controller_manager::InterpolatingController::execTrajectory
void execTrajectory(const moveit_msgs::RobotTrajectory &t) override
Definition: moveit_fake_controllers.cpp:251
moveit_fake_controller_manager::ThreadedController::waitForExecution
bool waitForExecution(const ros::Duration &) override
Definition: moveit_fake_controllers.cpp:172
ROS_DEBUG
#define ROS_DEBUG(...)
moveit_fake_controller_manager::InterpolatingController::~InterpolatingController
~InterpolatingController() override
moveit_fake_controller_manager::BaseFakeController::BaseFakeController
BaseFakeController(const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub)
Definition: moveit_fake_controllers.cpp:79
moveit_fake_controllers.h
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
moveit_fake_controller_manager::ThreadedController::getLastExecutionStatus
moveit_controller_manager::ExecutionStatus getLastExecutionStatus() override
Definition: moveit_fake_controllers.cpp:179
ros::WallRate::sleep
bool sleep()
moveit_fake_controller_manager::BaseFakeController::getLastExecutionStatus
moveit_controller_manager::ExecutionStatus getLastExecutionStatus() override
Definition: moveit_fake_controllers.cpp:95
name
std::string name
moveit_controller_manager::ExecutionStatus::SUCCEEDED
SUCCEEDED
ros::WallRate
moveit_fake_controller_manager::ThreadedController::cancelTrajectory
virtual void cancelTrajectory()
Definition: moveit_fake_controllers.cpp:149
moveit_fake_controller_manager::ThreadedController
Definition: moveit_fake_controllers.h:109
prev
EndPoint * prev[3]
next
EndPoint * next[3]
moveit_fake_controller_manager::ViaPointController::ViaPointController
ViaPointController(const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub)
Definition: moveit_fake_controllers.cpp:184
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
moveit_fake_controller_manager
Definition: moveit_fake_controller_manager.cpp:46
moveit_fake_controller_manager::ThreadedController::~ThreadedController
~ThreadedController() override
Definition: moveit_fake_controllers.cpp:144
r
S r
moveit_fake_controller_manager::ThreadedController::sendTrajectory
bool sendTrajectory(const moveit_msgs::RobotTrajectory &t) override
Definition: moveit_fake_controllers.cpp:155
moveit_fake_controller_manager::ThreadedController::cancelled
bool cancelled()
Definition: moveit_fake_controllers.h:121
moveit_fake_controller_manager::ThreadedController::status_
moveit_controller_manager::ExecutionStatus status_
Definition: moveit_fake_controllers.h:133
moveit_fake_controller_manager::ThreadedController::cancel_
bool cancel_
Definition: moveit_fake_controllers.h:132
moveit_fake_controller_manager::BaseFakeController::pub_
const ros::Publisher & pub_
Definition: moveit_fake_controllers.h:95
moveit_fake_controller_manager::BaseFakeController::getJoints
void getJoints(std::vector< std::string > &joints) const
Definition: moveit_fake_controllers.cpp:90
moveit_fake_controller_manager::ThreadedController::cancelExecution
bool cancelExecution() override
Definition: moveit_fake_controllers.cpp:164
ros::Time
moveit_fake_controller_manager::InterpolatingController::InterpolatingController
InterpolatingController(const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub)
Definition: moveit_fake_controllers.cpp:222
moveit_fake_controller_manager::ThreadedController::thread_
boost::thread thread_
Definition: moveit_fake_controllers.h:131
ros::Duration::sleep
bool sleep() const
DurationBase< Duration >::toSec
double toSec() const
moveit_fake_controller_manager::ThreadedController::ThreadedController
ThreadedController(const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub)
Definition: moveit_fake_controllers.cpp:138
ROS_INFO
#define ROS_INFO(...)
ros::Duration
param.h
moveit_controller_manager::ExecutionStatus
t
geometry_msgs::TransformStamped t
moveit_fake_controller_manager::ViaPointController::execTrajectory
void execTrajectory(const moveit_msgs::RobotTrajectory &t) override
Definition: moveit_fake_controllers.cpp:192
ros::Time::now
static Time now()
moveit_fake_controller_manager::LastPointController::waitForExecution
bool waitForExecution(const ros::Duration &) override
Definition: moveit_fake_controllers.cpp:132


moveit_fake_controller_manager
Author(s): Ioan Sucan
autogenerated on Sat May 3 2025 02:26:28