moveit2
The MoveIt Motion Planning Framework for ROS 2.
current_state_monitor.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
39 
40 #include <tf2_eigen/tf2_eigen.hpp>
41 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
42 
43 #include <chrono>
44 #include <limits>
45 #include <memory>
46 
47 namespace planning_scene_monitor
48 {
49 using namespace std::chrono_literals;
50 
51 namespace
52 {
53 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_ros.current_state_monitor");
54 }
55 
56 CurrentStateMonitor::CurrentStateMonitor(std::unique_ptr<CurrentStateMonitor::MiddlewareHandle> middleware_handle,
57  const moveit::core::RobotModelConstPtr& robot_model,
58  const std::shared_ptr<tf2_ros::Buffer>& tf_buffer, bool use_sim_time)
59  : middleware_handle_(std::move(middleware_handle))
60  , tf_buffer_(tf_buffer)
61  , robot_model_(robot_model)
62  , robot_state_(robot_model)
63  , state_monitor_started_(false)
64  , copy_dynamics_(false)
65  , error_(std::numeric_limits<double>::epsilon())
66  , use_sim_time_(use_sim_time)
67 {
68  robot_state_.setToDefaultValues();
69 }
70 
71 CurrentStateMonitor::CurrentStateMonitor(const rclcpp::Node::SharedPtr& node,
72  const moveit::core::RobotModelConstPtr& robot_model,
73  const std::shared_ptr<tf2_ros::Buffer>& tf_buffer, bool use_sim_time)
74  : CurrentStateMonitor(std::make_unique<CurrentStateMonitorMiddlewareHandle>(node), robot_model, tf_buffer,
75  use_sim_time)
76 {
77 }
78 
80 {
82 }
83 
84 moveit::core::RobotStatePtr CurrentStateMonitor::getCurrentState() const
85 {
86  std::unique_lock<std::mutex> slock(state_update_lock_);
87  moveit::core::RobotState* result = new moveit::core::RobotState(robot_state_);
88  return moveit::core::RobotStatePtr(result);
89 }
90 
92 {
93  std::unique_lock<std::mutex> slock(state_update_lock_);
94  return current_state_time_;
95 }
96 
97 std::pair<moveit::core::RobotStatePtr, rclcpp::Time> CurrentStateMonitor::getCurrentStateAndTime() const
98 {
99  std::unique_lock<std::mutex> slock(state_update_lock_);
100  moveit::core::RobotState* result = new moveit::core::RobotState(robot_state_);
101  return std::make_pair(moveit::core::RobotStatePtr(result), current_state_time_);
102 }
103 
104 std::map<std::string, double> CurrentStateMonitor::getCurrentStateValues() const
105 {
106  std::map<std::string, double> m;
107  std::unique_lock<std::mutex> slock(state_update_lock_);
108  const double* pos = robot_state_.getVariablePositions();
109  const std::vector<std::string>& names = robot_state_.getVariableNames();
110  for (std::size_t i = 0; i < names.size(); ++i)
111  m[names[i]] = pos[i];
112  return m;
113 }
114 
116 {
117  std::unique_lock<std::mutex> slock(state_update_lock_);
118  const double* pos = robot_state_.getVariablePositions();
119  upd.setVariablePositions(pos);
120  if (copy_dynamics_)
121  {
122  if (robot_state_.hasVelocities())
123  {
124  const double* vel = robot_state_.getVariableVelocities();
125  upd.setVariableVelocities(vel);
126  }
127  if (robot_state_.hasAccelerations())
128  {
129  const double* acc = robot_state_.getVariableAccelerations();
130  upd.setVariableAccelerations(acc);
131  }
132  if (robot_state_.hasEffort())
133  {
134  const double* eff = robot_state_.getVariableEffort();
135  upd.setVariableEffort(eff);
136  }
137  }
138 }
139 
141 {
142  if (fn)
143  update_callbacks_.push_back(fn);
144 }
145 
147 {
148  update_callbacks_.clear();
149 }
150 
151 void CurrentStateMonitor::startStateMonitor(const std::string& joint_states_topic)
152 {
153  if (!state_monitor_started_ && robot_model_)
154  {
155  joint_time_.clear();
156  if (joint_states_topic.empty())
157  {
158  RCLCPP_ERROR(LOGGER, "The joint states topic cannot be an empty string");
159  }
160  else
161  {
162  middleware_handle_->createJointStateSubscription(
163  joint_states_topic, [this](const sensor_msgs::msg::JointState::ConstSharedPtr& joint_state) {
164  return jointStateCallback(joint_state);
165  });
166  }
167  if (tf_buffer_ && !robot_model_->getMultiDOFJointModels().empty())
168  {
169  tf_buffer_->setUsingDedicatedThread(true);
170  middleware_handle_->createDynamicTfSubscription([this](const auto& msg) { return transformCallback(msg, false); });
171  middleware_handle_->createStaticTfSubscription([this](const auto& msg) { return transformCallback(msg, true); });
172  }
173  state_monitor_started_ = true;
174  monitor_start_time_ = middleware_handle_->now();
175  RCLCPP_INFO(LOGGER, "Listening to joint states on topic '%s'", joint_states_topic.c_str());
176  }
177 }
178 
180 {
181  return state_monitor_started_;
182 }
183 
185 {
186  if (state_monitor_started_)
187  {
188  middleware_handle_->resetJointStateSubscription();
189  if (tf_buffer_)
190  {
191  middleware_handle_->resetTfSubscriptions();
192  }
193  RCLCPP_DEBUG(LOGGER, "No longer listening for joint states");
194  state_monitor_started_ = false;
195  }
196 }
197 
199 {
200  return middleware_handle_->getJointStateTopicName();
201 }
202 
203 bool CurrentStateMonitor::haveCompleteStateHelper(const rclcpp::Time& oldest_allowed_update_time,
204  std::vector<std::string>* missing_joints) const
205 {
206  const std::vector<const moveit::core::JointModel*>& active_joints = robot_model_->getActiveJointModels();
207  std::unique_lock<std::mutex> slock(state_update_lock_);
208  for (const moveit::core::JointModel* joint : active_joints)
209  {
210  std::map<const moveit::core::JointModel*, rclcpp::Time>::const_iterator it = joint_time_.find(joint);
211  if (it == joint_time_.end())
212  {
213  RCLCPP_DEBUG(LOGGER, "Joint '%s' has never been updated", joint->getName().c_str());
214  }
215  else if (it->second < oldest_allowed_update_time)
216  {
217  RCLCPP_DEBUG(LOGGER, "Joint '%s' was last updated %0.3lf seconds before requested time", joint->getName().c_str(),
218  (oldest_allowed_update_time - it->second).seconds());
219  }
220  else
221  continue;
222 
223  if (missing_joints)
224  missing_joints->push_back(joint->getName());
225  else
226  return false;
227  }
228  return (missing_joints == nullptr) || missing_joints->empty();
229 }
230 
231 bool CurrentStateMonitor::waitForCurrentState(const rclcpp::Time& t, double wait_time_s) const
232 {
233  rclcpp::Time start = middleware_handle_->now();
234  rclcpp::Duration elapsed(0, 0);
235  rclcpp::Duration timeout = rclcpp::Duration::from_seconds(wait_time_s);
236 
237  rclcpp::Clock steady_clock(RCL_STEADY_TIME);
238  std::unique_lock<std::mutex> lock(state_update_lock_);
239  while (current_state_time_ < t)
240  {
241  if (use_sim_time_)
242  {
243  if (state_update_condition_.wait_for(lock, 100ms) == std::cv_status::timeout)
244  {
245  /* We cannot know if the reason of timeout is slow time or absence of
246  * state messages, warn the user. */
247  RCLCPP_WARN_SKIPFIRST_THROTTLE(LOGGER, steady_clock, 1000,
248  "No state update received within 100ms of system clock. "
249  "Have been waiting for %fs, timeout is %fs",
250  elapsed.seconds(), wait_time_s);
251  }
252  }
253  else
254  {
255  state_update_condition_.wait_for(lock, (timeout - elapsed).to_chrono<std::chrono::duration<double>>());
256  }
257  elapsed = middleware_handle_->now() - start;
258  if (elapsed > timeout)
259  {
260  RCLCPP_INFO(LOGGER,
261  "Didn't receive robot state (joint angles) with recent timestamp within "
262  "%f seconds. Requested time %f, but latest received state has time %f.\n"
263  "Check clock synchronization if your are running ROS across multiple machines!",
264  wait_time_s, t.seconds(), current_state_time_.seconds());
265  return false;
266  }
267  if (!middleware_handle_->ok())
268  {
269  RCLCPP_DEBUG(LOGGER, "ROS context shut down while waiting for current robot state.");
270  return false;
271  }
272  }
273  return true;
274 }
275 
276 bool CurrentStateMonitor::waitForCompleteState(double wait_time_s) const
277 {
278  const double sleep_step_s = std::min(0.05, wait_time_s / 10.0);
279  const auto sleep_step_duration = rclcpp::Duration::from_seconds(sleep_step_s);
280  double slept_time_s = 0.0;
281  while (!haveCompleteState() && slept_time_s < wait_time_s)
282  {
283  middleware_handle_->sleepFor(sleep_step_duration.to_chrono<std::chrono::nanoseconds>());
284  slept_time_s += sleep_step_s;
285  }
286  return haveCompleteState();
287 }
288 
289 bool CurrentStateMonitor::waitForCompleteState(const std::string& group, double wait_time_s) const
290 {
291  if (waitForCompleteState(wait_time_s))
292  return true;
293  bool ok = true;
294 
295  // check to see if we have a fully known state for the joints we want to record
296  std::vector<std::string> missing_joints;
297  if (!haveCompleteState(missing_joints))
298  {
299  const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(group);
300  if (jmg)
301  {
302  std::set<std::string> mj;
303  mj.insert(missing_joints.begin(), missing_joints.end());
304  const std::vector<std::string>& names = jmg->getJointModelNames();
305  bool ok = true;
306  for (std::size_t i = 0; ok && i < names.size(); ++i)
307  if (mj.find(names[i]) != mj.end())
308  ok = false;
309  }
310  else
311  ok = false;
312  }
313  return ok;
314 }
315 
316 void CurrentStateMonitor::jointStateCallback(const sensor_msgs::msg::JointState::ConstSharedPtr& joint_state)
317 {
318  if (joint_state->name.size() != joint_state->position.size())
319  {
320  rclcpp::Clock steady_clock(RCL_STEADY_TIME);
321  RCLCPP_ERROR_THROTTLE(LOGGER, steady_clock, 1000,
322  "State monitor received invalid joint state (number of joint names does not match number of "
323  "positions)");
324  return;
325  }
326  bool update = false;
327 
328  {
329  std::unique_lock<std::mutex> _(state_update_lock_);
330  // read the received values, and update their time stamps
331  std::size_t n = joint_state->name.size();
332  current_state_time_ = joint_state->header.stamp;
333  for (std::size_t i = 0; i < n; ++i)
334  {
335  const moveit::core::JointModel* jm = robot_model_->getJointModel(joint_state->name[i]);
336  if (!jm)
337  continue;
338  // ignore fixed joints, multi-dof joints (they should not even be in the message)
339  if (jm->getVariableCount() != 1)
340  continue;
341 
342  joint_time_.insert_or_assign(jm, joint_state->header.stamp);
343 
344  if (robot_state_.getJointPositions(jm)[0] != joint_state->position[i])
345  {
346  update = true;
347  robot_state_.setJointPositions(jm, &(joint_state->position[i]));
348 
349  // continuous joints wrap, so we don't modify them (even if they are outside bounds!)
351  if (static_cast<const moveit::core::RevoluteJointModel*>(jm)->isContinuous())
352  continue;
353 
355  jm->getVariableBounds()[0]; // only one variable in the joint, so we get its bounds
356 
357  // if the read variable is 'almost' within bounds (up to error_ difference), then consider it to be within
358  // bounds
359  if (joint_state->position[i] < b.min_position_ && joint_state->position[i] >= b.min_position_ - error_)
360  robot_state_.setJointPositions(jm, &b.min_position_);
361  else if (joint_state->position[i] > b.max_position_ && joint_state->position[i] <= b.max_position_ + error_)
362  robot_state_.setJointPositions(jm, &b.max_position_);
363  }
364 
365  // optionally copy velocities and effort
366  if (copy_dynamics_)
367  {
368  // update joint velocities
369  if (joint_state->name.size() == joint_state->velocity.size() &&
370  (!robot_state_.hasVelocities() || robot_state_.getJointVelocities(jm)[0] != joint_state->velocity[i]))
371  {
372  update = true;
373  robot_state_.setJointVelocities(jm, &(joint_state->velocity[i]));
374  }
375 
376  // update joint efforts
377  if (joint_state->name.size() == joint_state->effort.size() &&
378  (!robot_state_.hasEffort() || robot_state_.getJointEffort(jm)[0] != joint_state->effort[i]))
379  {
380  update = true;
381  robot_state_.setJointEfforts(jm, &(joint_state->effort[i]));
382  }
383  }
384  }
385  }
386 
387  // callbacks, if needed
388  if (update)
389  for (JointStateUpdateCallback& update_callback : update_callbacks_)
390  update_callback(joint_state);
391 
392  // notify waitForCurrentState() *after* potential update callbacks
393  state_update_condition_.notify_all();
394 }
395 
396 void CurrentStateMonitor::updateMultiDofJoints()
397 {
398  // read multi-dof joint states from TF, if needed
399  const std::vector<const moveit::core::JointModel*>& multi_dof_joints = robot_model_->getMultiDOFJointModels();
400 
401  bool update = false;
402  bool changes = false;
403  {
404  std::unique_lock<std::mutex> _(state_update_lock_);
405  for (const moveit::core::JointModel* joint : multi_dof_joints)
406  {
407  const std::string& child_frame = joint->getChildLinkModel()->getName();
408  const std::string& parent_frame =
409  joint->getParentLinkModel() ? joint->getParentLinkModel()->getName() : robot_model_->getModelFrame();
410 
411  rclcpp::Time latest_common_time(0, 0, RCL_ROS_TIME);
412  geometry_msgs::msg::TransformStamped transf;
413  try
414  {
415  transf = tf_buffer_->lookupTransform(parent_frame, child_frame, tf2::TimePointZero);
416  latest_common_time = transf.header.stamp;
417  }
418  catch (tf2::TransformException& ex)
419  {
420  RCLCPP_WARN_ONCE(LOGGER,
421  "Unable to update multi-DOF joint '%s':"
422  "Failure to lookup transform between '%s'"
423  "and '%s' with TF exception: %s",
424  joint->getName().c_str(), parent_frame.c_str(), child_frame.c_str(), ex.what());
425  continue;
426  }
427 
428  if (auto joint_time_it = joint_time_.find(joint); joint_time_it == joint_time_.end())
429  joint_time_.emplace(joint, rclcpp::Time(0, 0, RCL_ROS_TIME));
430 
431  // allow update if time is more recent or if it is a static transform (time = 0)
432  if (latest_common_time <= joint_time_[joint] && latest_common_time > rclcpp::Time(0, 0, RCL_ROS_TIME))
433  continue;
434  joint_time_[joint] = latest_common_time;
435 
436  std::vector<double> new_values(joint->getStateSpaceDimension());
437  const moveit::core::LinkModel* link = joint->getChildLinkModel();
438  if (link->jointOriginTransformIsIdentity())
439  joint->computeVariablePositions(tf2::transformToEigen(transf), new_values.data());
440  else
441  joint->computeVariablePositions(link->getJointOriginTransform().inverse() * tf2::transformToEigen(transf),
442  new_values.data());
443 
444  if (joint->distance(new_values.data(), robot_state_.getJointPositions(joint)) > 1e-5)
445  {
446  changes = true;
447  }
448 
449  robot_state_.setJointPositions(joint, new_values.data());
450  update = true;
451  }
452  }
453 
454  // callbacks, if needed
455  if (changes)
456  {
457  // stub joint state: multi-dof joints are not modelled in the message,
458  // but we should still trigger the update callbacks
459  auto joint_state = std::make_shared<sensor_msgs::msg::JointState>();
460  for (JointStateUpdateCallback& update_callback : update_callbacks_)
461  update_callback(joint_state);
462  }
463 
464  if (update)
465  {
466  // notify waitForCurrentState() *after* potential update callbacks
467  state_update_condition_.notify_all();
468  }
469 }
470 
471 // Copied from https://github.com/ros2/geometry2/blob/ros2/tf2_ros/src/transform_listener.cpp
472 void CurrentStateMonitor::transformCallback(const tf2_msgs::msg::TFMessage::ConstSharedPtr& msg, const bool is_static)
473 {
474  for (const auto& transform : msg->transforms)
475  {
476  try
477  {
478  tf_buffer_->setTransform(transform,
479  is_static ? middleware_handle_->getStaticTfTopicName() :
480  middleware_handle_->getDynamicTfTopicName(),
481  is_static);
482  }
483  catch (tf2::TransformException& ex)
484  {
485  std::string temp = ex.what();
486  RCLCPP_ERROR(LOGGER, "Failure to set received transform from %s to %s with error: %s\n",
487  transform.child_frame_id.c_str(), transform.header.frame_id.c_str(), temp.c_str());
488  }
489  }
490  updateMultiDofJoints();
491 }
492 } // namespace planning_scene_monitor
const std::vector< std::string > & getJointModelNames() const
Get the names of the joints in this group. These are the names of the joints returned by getJointMode...
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:117
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
Definition: joint_model.h:210
const VariableBounds & getVariableBounds(const std::string &variable) const
Get the bounds for a variable. Throw an exception if the variable was not found.
JointType getType() const
Get the type of joint.
Definition: joint_model.h:151
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition: link_model.h:72
bool jointOriginTransformIsIdentity() const
Definition: link_model.h:148
const Eigen::Isometry3d & getJointOriginTransform() const
When transforms are computed for this link, they are usually applied to the link's origin....
Definition: link_model.h:143
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
void setVariablePositions(const double *position)
It is assumed positions is an array containing the new positions for all variables in this state....
void setJointEfforts(const JointModel *joint, const double *effort)
void setJointVelocities(const JointModel *joint, const double *velocity)
Definition: robot_state.h:549
const double * getJointEffort(const std::string &joint_name) const
Definition: robot_state.h:587
const double * getJointPositions(const std::string &joint_name) const
Definition: robot_state.h:557
bool hasVelocities() const
By default, if velocities are never set or initialized, the state remembers that there are no velocit...
Definition: robot_state.h:229
bool hasAccelerations() const
By default, if accelerations are never set or initialized, the state remembers that there are no acce...
Definition: robot_state.h:322
void setVariableVelocities(const double *velocity)
Given an array with velocity values for all variables, set those values as the velocities in this sta...
Definition: robot_state.h:253
double * getVariablePositions()
Get a raw pointer to the positions of the variables stored in this state. Use carefully....
Definition: robot_state.h:147
const double * getJointVelocities(const std::string &joint_name) const
Definition: robot_state.h:567
bool hasEffort() const
By default, if effort is never set or initialized, the state remembers that there is no effort set....
Definition: robot_state.h:420
double * getVariableVelocities()
Get raw access to the velocities of the variables that make up this state. The values are in the same...
Definition: robot_state.h:236
double * getVariableEffort()
Get raw access to the effort of the variables that make up this state. The values are in the same ord...
Definition: robot_state.h:428
void setVariableEffort(const double *effort)
Given an array with effort values for all variables, set those values as the effort in this state.
Definition: robot_state.h:445
void setVariableAccelerations(const double *acceleration)
Given an array with acceleration values for all variables, set those values as the accelerations in t...
Definition: robot_state.h:348
double * getVariableAccelerations()
Get raw access to the accelerations of the variables that make up this state. The values are in the s...
Definition: robot_state.h:330
const std::vector< std::string > & getVariableNames() const
Get the names of the variables that make up this state, in the order they are stored in memory.
Definition: robot_state.h:116
void setJointPositions(const std::string &joint_name, const double *position)
Definition: robot_state.h:515
This class contains the ros interfaces for CurrentStateMontior.
Monitors the joint_states topic and tf to maintain the current state of the robot.
void startStateMonitor(const std::string &joint_states_topic="joint_states")
Start monitoring joint states on a particular topic.
bool isActive() const
Check if the state monitor is started.
void clearUpdateCallbacks()
Clear the functions to be called when an update to the joint state is received.
std::map< std::string, double > getCurrentStateValues() const
Get the current state values as a map from joint names to joint state values.
void addUpdateCallback(const JointStateUpdateCallback &fn)
Add a function that will be called whenever the joint state is updated.
std::pair< moveit::core::RobotStatePtr, rclcpp::Time > getCurrentStateAndTime() const
Get the current state and its time stamp.
void setToCurrentState(moveit::core::RobotState &upd) const
Set the state upd to the current state maintained by this class.
bool waitForCurrentState(const rclcpp::Time &t=rclcpp::Clock(RCL_ROS_TIME).now(), double wait_time_s=1.0) const
Wait for at most wait_time_s seconds (default 1s) for a robot state more recent than t.
rclcpp::Time getCurrentStateTime() const
Get the time stamp for the current state.
bool haveCompleteState() const
Query whether we have joint state information for all DOFs in the kinematic model.
void stopStateMonitor()
Stop monitoring the "joint_states" topic.
moveit::core::RobotStatePtr getCurrentState() const
Get the current state.
CurrentStateMonitor(std::unique_ptr< MiddlewareHandle > middleware_handle, const moveit::core::RobotModelConstPtr &robot_model, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer, bool use_sim_time)
Constructor.
std::string getMonitoredTopic() const
Get the name of the topic being monitored. Returns an empty string if the monitor is inactive.
bool waitForCompleteState(double wait_time_s) const
Wait for at most wait_time_s seconds until the complete robot state is known.
std::function< void(sensor_msgs::msg::JointState::ConstSharedPtr)> JointStateUpdateCallback
const rclcpp::Logger LOGGER
Definition: async_test.h:31