moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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
40
41#include <tf2_eigen/tf2_eigen.hpp>
42#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
43
44#include <chrono>
45#include <limits>
46#include <memory>
47
49{
50using namespace std::chrono_literals;
51
52CurrentStateMonitor::CurrentStateMonitor(std::unique_ptr<CurrentStateMonitor::MiddlewareHandle> middleware_handle,
53 const moveit::core::RobotModelConstPtr& robot_model,
54 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer, bool use_sim_time)
55 : middleware_handle_(std::move(middleware_handle))
56 , tf_buffer_(tf_buffer)
57 , robot_model_(robot_model)
58 , robot_state_(robot_model)
59 , state_monitor_started_(false)
60 , copy_dynamics_(false)
61 , error_(std::numeric_limits<double>::epsilon())
62 , use_sim_time_(use_sim_time)
63 , logger_(moveit::getLogger("moveit.ros.current_state_monitor"))
64{
65 robot_state_.setToDefaultValues();
66}
67
68CurrentStateMonitor::CurrentStateMonitor(const rclcpp::Node::SharedPtr& node,
69 const moveit::core::RobotModelConstPtr& robot_model,
70 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer, bool use_sim_time)
71 : CurrentStateMonitor(std::make_unique<CurrentStateMonitorMiddlewareHandle>(node), robot_model, tf_buffer,
72 use_sim_time)
73{
74}
75
80
81moveit::core::RobotStatePtr CurrentStateMonitor::getCurrentState() const
82{
83 std::unique_lock<std::mutex> slock(state_update_lock_);
84 moveit::core::RobotState* result = new moveit::core::RobotState(robot_state_);
85 return moveit::core::RobotStatePtr(result);
86}
87
89{
90 std::unique_lock<std::mutex> slock(state_update_lock_);
91 return current_state_time_;
92}
93
94std::pair<moveit::core::RobotStatePtr, rclcpp::Time> CurrentStateMonitor::getCurrentStateAndTime() const
95{
96 std::unique_lock<std::mutex> slock(state_update_lock_);
97 moveit::core::RobotState* result = new moveit::core::RobotState(robot_state_);
98 return std::make_pair(moveit::core::RobotStatePtr(result), current_state_time_);
99}
100
101std::map<std::string, double> CurrentStateMonitor::getCurrentStateValues() const
102{
103 std::map<std::string, double> m;
104 std::unique_lock<std::mutex> slock(state_update_lock_);
105 const double* pos = robot_state_.getVariablePositions();
106 const std::vector<std::string>& names = robot_state_.getVariableNames();
107 for (std::size_t i = 0; i < names.size(); ++i)
108 m[names[i]] = pos[i];
109 return m;
110}
111
113{
114 std::unique_lock<std::mutex> slock(state_update_lock_);
115 const double* pos = robot_state_.getVariablePositions();
116 upd.setVariablePositions(pos);
117 if (copy_dynamics_)
118 {
119 if (robot_state_.hasVelocities())
120 {
121 const double* vel = robot_state_.getVariableVelocities();
122 upd.setVariableVelocities(vel);
123 }
124 if (robot_state_.hasAccelerations())
125 {
126 const double* acc = robot_state_.getVariableAccelerations();
128 }
129 if (robot_state_.hasEffort())
130 {
131 const double* eff = robot_state_.getVariableEffort();
132 upd.setVariableEffort(eff);
133 }
134 }
135}
136
138{
139 if (fn)
140 update_callbacks_.push_back(fn);
141}
142
144{
145 update_callbacks_.clear();
146}
147
148void CurrentStateMonitor::startStateMonitor(const std::string& joint_states_topic)
149{
150 if (!state_monitor_started_ && robot_model_)
151 {
152 joint_time_.clear();
153 if (joint_states_topic.empty())
154 {
155 RCLCPP_ERROR(logger_, "The joint states topic cannot be an empty string");
156 }
157 else
158 {
159 middleware_handle_->createJointStateSubscription(
160 joint_states_topic, [this](const sensor_msgs::msg::JointState::ConstSharedPtr& joint_state) {
161 return jointStateCallback(joint_state);
162 });
163 }
164 if (tf_buffer_ && !robot_model_->getMultiDOFJointModels().empty())
165 {
166 tf_buffer_->setUsingDedicatedThread(true);
167 middleware_handle_->createDynamicTfSubscription([this](const auto& msg) { return transformCallback(msg, false); });
168 middleware_handle_->createStaticTfSubscription([this](const auto& msg) { return transformCallback(msg, true); });
169 }
170 state_monitor_started_ = true;
171 monitor_start_time_ = middleware_handle_->now();
172 RCLCPP_INFO(logger_, "Listening to joint states on topic '%s'", joint_states_topic.c_str());
173 }
174}
175
177{
178 return state_monitor_started_;
179}
180
182{
183 if (state_monitor_started_)
184 {
185 middleware_handle_->resetJointStateSubscription();
186 if (tf_buffer_)
187 {
188 middleware_handle_->resetTfSubscriptions();
189 }
190 RCLCPP_DEBUG(logger_, "No longer listening for joint states");
191 state_monitor_started_ = false;
192 }
193}
194
196{
197 return middleware_handle_->getJointStateTopicName();
198}
199
200bool CurrentStateMonitor::haveCompleteStateHelper(const rclcpp::Time& oldest_allowed_update_time,
201 std::vector<std::string>* missing_joints) const
202{
203 const std::vector<const moveit::core::JointModel*>& active_joints = robot_model_->getActiveJointModels();
204 std::unique_lock<std::mutex> slock(state_update_lock_);
205 for (const moveit::core::JointModel* joint : active_joints)
206 {
207 std::map<const moveit::core::JointModel*, rclcpp::Time>::const_iterator it = joint_time_.find(joint);
208 if (it == joint_time_.end())
209 {
210 RCLCPP_DEBUG(logger_, "Joint '%s' has never been updated", joint->getName().c_str());
211 }
212 else if (it->second < oldest_allowed_update_time)
213 {
214 RCLCPP_DEBUG(logger_, "Joint '%s' was last updated %0.3lf seconds before requested time",
215 joint->getName().c_str(), (oldest_allowed_update_time - it->second).seconds());
216 }
217 else
218 continue;
219
220 if (missing_joints)
221 {
222 missing_joints->push_back(joint->getName());
223 }
224 else
225 {
226 return false;
227 }
228 }
229 return (missing_joints == nullptr) || missing_joints->empty();
230}
231
232bool CurrentStateMonitor::waitForCurrentState(const rclcpp::Time& t, double wait_time_s) const
233{
234 rclcpp::Time start = middleware_handle_->now();
235 rclcpp::Duration elapsed(0, 0);
236 rclcpp::Duration timeout = rclcpp::Duration::from_seconds(wait_time_s);
237
238 rclcpp::Clock steady_clock(RCL_STEADY_TIME);
239 std::unique_lock<std::mutex> lock(state_update_lock_);
240 while (current_state_time_ < t)
241 {
242 if (use_sim_time_)
243 {
244 if (state_update_condition_.wait_for(lock, 100ms) == std::cv_status::timeout)
245 {
246 /* We cannot know if the reason of timeout is slow time or absence of
247 * state messages, warn the user. */
248#pragma GCC diagnostic push
249#pragma GCC diagnostic ignored "-Wold-style-cast"
250 RCLCPP_WARN_SKIPFIRST_THROTTLE(logger_, steady_clock, 1000,
251 "No state update received within 100ms of system clock. "
252 "Have been waiting for %fs, timeout is %fs",
253 elapsed.seconds(), wait_time_s);
254#pragma GCC diagnostic pop
255 }
256 }
257 else
258 {
259 state_update_condition_.wait_for(lock, (timeout - elapsed).to_chrono<std::chrono::duration<double>>());
260 }
261 elapsed = middleware_handle_->now() - start;
262 if (elapsed > timeout)
263 {
264 RCLCPP_INFO(logger_,
265 "Didn't receive robot state (joint angles) with recent timestamp within "
266 "%f seconds. Requested time %f, but latest received state has time %f.\n"
267 "Check clock synchronization if your are running ROS across multiple machines!",
268 wait_time_s, t.seconds(), current_state_time_.seconds());
269 return false;
270 }
271 if (!middleware_handle_->ok())
272 {
273 RCLCPP_DEBUG(logger_, "ROS context shut down while waiting for current robot state.");
274 return false;
275 }
276 }
277 return true;
278}
279
280bool CurrentStateMonitor::waitForCompleteState(double wait_time_s) const
281{
282 const double sleep_step_s = std::min(0.05, wait_time_s / 10.0);
283 const auto sleep_step_duration = rclcpp::Duration::from_seconds(sleep_step_s);
284 double slept_time_s = 0.0;
285 while (!haveCompleteState() && slept_time_s < wait_time_s)
286 {
287 middleware_handle_->sleepFor(sleep_step_duration.to_chrono<std::chrono::nanoseconds>());
288 slept_time_s += sleep_step_s;
289 }
290 return haveCompleteState();
291}
292
293bool CurrentStateMonitor::waitForCompleteState(const std::string& group, double wait_time_s) const
294{
295 if (waitForCompleteState(wait_time_s))
296 return true;
297 bool ok = true;
298
299 // check to see if we have a fully known state for the joints we want to record
300 std::vector<std::string> missing_joints;
301 if (!haveCompleteState(missing_joints))
302 {
303 const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(group);
304 if (jmg)
305 {
306 std::set<std::string> mj;
307 mj.insert(missing_joints.begin(), missing_joints.end());
308 const std::vector<std::string>& names = jmg->getJointModelNames();
309 bool ok = true;
310 for (std::size_t i = 0; ok && i < names.size(); ++i)
311 {
312 if (mj.find(names[i]) != mj.end())
313 ok = false;
314 }
315 }
316 else
317 ok = false;
318 }
319 return ok;
320}
321
322void CurrentStateMonitor::jointStateCallback(const sensor_msgs::msg::JointState::ConstSharedPtr& joint_state)
323{
324 if (joint_state->name.size() != joint_state->position.size())
325 {
326 rclcpp::Clock steady_clock(RCL_STEADY_TIME);
327#pragma GCC diagnostic push
328#pragma GCC diagnostic ignored "-Wold-style-cast"
329 RCLCPP_ERROR_THROTTLE(logger_, steady_clock, 1000,
330 "State monitor received invalid joint state (number of joint names does not match number of "
331 "positions)");
332#pragma GCC diagnostic pop
333 return;
334 }
335 bool update = false;
336
337 {
338 std::unique_lock<std::mutex> _(state_update_lock_);
339 // read the received values, and update their time stamps
340 std::size_t n = joint_state->name.size();
341 current_state_time_ = joint_state->header.stamp;
342 for (std::size_t i = 0; i < n; ++i)
343 {
344 // Skip joints that don't belong to the RobotModel
345 if (!robot_model_->hasJointModel(joint_state->name[i]))
346 {
347 continue;
348 }
349
350 const moveit::core::JointModel* jm = robot_model_->getJointModel(joint_state->name[i]);
351 // ignore fixed joints, multi-dof joints (they should not even be in the message)
352 if (jm->getVariableCount() != 1)
353 continue;
354
355 joint_time_.insert_or_assign(jm, joint_state->header.stamp);
356
357 if (robot_state_.getJointPositions(jm)[0] != joint_state->position[i])
358 {
359 update = true;
360 robot_state_.setJointPositions(jm, &(joint_state->position[i]));
361
362 // continuous joints wrap, so we don't modify them (even if they are outside bounds!)
364 {
365 if (static_cast<const moveit::core::RevoluteJointModel*>(jm)->isContinuous())
366 continue;
367 }
368
370 jm->getVariableBounds()[0]; // only one variable in the joint, so we get its bounds
371
372 // if the read variable is 'almost' within bounds (up to error_ difference), then consider it to be within
373 // bounds
374 if (joint_state->position[i] < b.min_position_ && joint_state->position[i] >= b.min_position_ - error_)
375 {
376 robot_state_.setJointPositions(jm, &b.min_position_);
377 }
378 else if (joint_state->position[i] > b.max_position_ && joint_state->position[i] <= b.max_position_ + error_)
379 {
380 robot_state_.setJointPositions(jm, &b.max_position_);
381 }
382 }
383
384 // optionally copy velocities and effort
385 if (copy_dynamics_)
386 {
387 // update joint velocities
388 if (joint_state->name.size() == joint_state->velocity.size() &&
389 (!robot_state_.hasVelocities() || robot_state_.getJointVelocities(jm)[0] != joint_state->velocity[i]))
390 {
391 update = true;
392 robot_state_.setJointVelocities(jm, &(joint_state->velocity[i]));
393 }
394
395 // update joint efforts
396 if (joint_state->name.size() == joint_state->effort.size() &&
397 (!robot_state_.hasEffort() || robot_state_.getJointEffort(jm)[0] != joint_state->effort[i]))
398 {
399 update = true;
400 robot_state_.setJointEfforts(jm, &(joint_state->effort[i]));
401 }
402 }
403 }
404 }
405
406 // callbacks, if needed
407 if (update)
408 {
409 for (JointStateUpdateCallback& update_callback : update_callbacks_)
410 update_callback(joint_state);
411 }
412
413 // notify waitForCurrentState() *after* potential update callbacks
414 state_update_condition_.notify_all();
415}
416
417void CurrentStateMonitor::updateMultiDofJoints()
418{
419 // read multi-dof joint states from TF, if needed
420 const std::vector<const moveit::core::JointModel*>& multi_dof_joints = robot_model_->getMultiDOFJointModels();
421
422 bool update = false;
423 bool changes = false;
424 {
425 std::unique_lock<std::mutex> _(state_update_lock_);
426 for (const moveit::core::JointModel* joint : multi_dof_joints)
427 {
428 const std::string& child_frame = joint->getChildLinkModel()->getName();
429 const std::string& parent_frame =
430 joint->getParentLinkModel() ? joint->getParentLinkModel()->getName() : robot_model_->getModelFrame();
431
432 rclcpp::Time latest_common_time(0, 0, RCL_ROS_TIME);
433 geometry_msgs::msg::TransformStamped transf;
434 try
435 {
436 transf = tf_buffer_->lookupTransform(parent_frame, child_frame, tf2::TimePointZero);
437 latest_common_time = transf.header.stamp;
438 }
439 catch (tf2::TransformException& ex)
440 {
441 RCLCPP_WARN_ONCE(logger_,
442 "Unable to update multi-DOF joint '%s':"
443 "Failure to lookup transform between '%s'"
444 "and '%s' with TF exception: %s",
445 joint->getName().c_str(), parent_frame.c_str(), child_frame.c_str(), ex.what());
446 continue;
447 }
448
449 if (auto joint_time_it = joint_time_.find(joint); joint_time_it == joint_time_.end())
450 joint_time_.emplace(joint, rclcpp::Time(0, 0, RCL_ROS_TIME));
451
452 // allow update if time is more recent or if it is a static transform (time = 0)
453 if (latest_common_time <= joint_time_[joint] && latest_common_time > rclcpp::Time(0, 0, RCL_ROS_TIME))
454 continue;
455 joint_time_[joint] = latest_common_time;
456
457 std::vector<double> new_values(joint->getStateSpaceDimension());
458 const moveit::core::LinkModel* link = joint->getChildLinkModel();
460 {
461 joint->computeVariablePositions(tf2::transformToEigen(transf), new_values.data());
462 }
463 else
464 {
465 joint->computeVariablePositions(link->getJointOriginTransform().inverse() * tf2::transformToEigen(transf),
466 new_values.data());
467 }
468
469 if (joint->distance(new_values.data(), robot_state_.getJointPositions(joint)) > 1e-5)
470 {
471 changes = true;
472 }
473
474 robot_state_.setJointPositions(joint, new_values.data());
475 update = true;
476 }
477 }
478
479 // callbacks, if needed
480 if (changes)
481 {
482 // stub joint state: multi-dof joints are not modelled in the message,
483 // but we should still trigger the update callbacks
484 auto joint_state = std::make_shared<sensor_msgs::msg::JointState>();
485 for (JointStateUpdateCallback& update_callback : update_callbacks_)
486 update_callback(joint_state);
487 }
488
489 if (update)
490 {
491 // notify waitForCurrentState() *after* potential update callbacks
492 state_update_condition_.notify_all();
493 }
494}
495
496// Copied from https://github.com/ros2/geometry2/blob/ros2/tf2_ros/src/transform_listener.cpp
497void CurrentStateMonitor::transformCallback(const tf2_msgs::msg::TFMessage::ConstSharedPtr& msg, const bool is_static)
498{
499 for (const auto& transform : msg->transforms)
500 {
501 try
502 {
503 tf_buffer_->setTransform(transform,
504 is_static ? middleware_handle_->getStaticTfTopicName() :
505 middleware_handle_->getDynamicTfTopicName(),
506 is_static);
507 }
508 catch (tf2::TransformException& ex)
509 {
510 std::string temp = ex.what();
511 RCLCPP_ERROR(logger_, "Failure to set received transform from %s to %s with error: %s\n",
512 transform.child_frame_id.c_str(), transform.header.frame_id.c_str(), temp.c_str());
513 }
514 }
515 updateMultiDofJoints();
516}
517} // 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....
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
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.
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)
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.
void setJointVelocities(const JointModel *joint, const double *velocity)
bool hasVelocities() const
By default, if velocities are never set or initialized, the state remembers that there are no velocit...
const double * getJointPositions(const std::string &joint_name) const
bool hasAccelerations() const
By default, if accelerations are never set or initialized, the state remembers that there are no acce...
void setVariableVelocities(const double *velocity)
Given an array with velocity values for all variables, set those values as the velocities in this sta...
const double * getJointEffort(const std::string &joint_name) const
const double * getJointVelocities(const std::string &joint_name) const
double * getVariablePositions()
Get a raw pointer to the positions of the variables stored in this state. Use carefully....
bool hasEffort() const
By default, if effort is never set or initialized, the state remembers that there is no effort set....
void setVariableEffort(const double *effort)
Given an array with effort values for all variables, set those values as the effort in this state.
void setVariableAccelerations(const double *acceleration)
Given an array with acceleration values for all variables, set those values as the accelerations in t...
double * getVariableVelocities()
Get raw access to the velocities of the variables that make up this state. The values are in the same...
double * getVariableEffort()
Get raw access to the effort of the variables that make up this state. The values are in the same ord...
double * getVariableAccelerations()
Get raw access to the accelerations of the variables that make up this state. The values are in the s...
void setJointPositions(const std::string &joint_name, const double *position)
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.
void update(moveit::core::RobotState *self, bool force, std::string &category)
Main namespace for MoveIt.
Definition exceptions.h:43
std::function< void(sensor_msgs::msg::JointState::ConstSharedPtr)> JointStateUpdateCallback