40 #include <tf2_eigen/tf2_eigen.hpp>
41 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
49 using namespace std::chrono_literals;
53 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_ros.current_state_monitor");
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)
68 robot_state_.setToDefaultValues();
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)
86 std::unique_lock<std::mutex> slock(state_update_lock_);
88 return moveit::core::RobotStatePtr(result);
93 std::unique_lock<std::mutex> slock(state_update_lock_);
94 return current_state_time_;
99 std::unique_lock<std::mutex> slock(state_update_lock_);
101 return std::make_pair(moveit::core::RobotStatePtr(result), current_state_time_);
106 std::map<std::string, double> m;
107 std::unique_lock<std::mutex> slock(state_update_lock_);
110 for (std::size_t i = 0; i < names.size(); ++i)
111 m[names[i]] = pos[i];
117 std::unique_lock<std::mutex> slock(state_update_lock_);
143 update_callbacks_.push_back(fn);
148 update_callbacks_.clear();
153 if (!state_monitor_started_ && robot_model_)
156 if (joint_states_topic.empty())
158 RCLCPP_ERROR(LOGGER,
"The joint states topic cannot be an empty string");
162 middleware_handle_->createJointStateSubscription(
163 joint_states_topic, [
this](
const sensor_msgs::msg::JointState::ConstSharedPtr& joint_state) {
164 return jointStateCallback(joint_state);
167 if (tf_buffer_ && !robot_model_->getMultiDOFJointModels().empty())
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); });
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());
181 return state_monitor_started_;
186 if (state_monitor_started_)
188 middleware_handle_->resetJointStateSubscription();
191 middleware_handle_->resetTfSubscriptions();
193 RCLCPP_DEBUG(LOGGER,
"No longer listening for joint states");
194 state_monitor_started_ =
false;
200 return middleware_handle_->getJointStateTopicName();
203 bool CurrentStateMonitor::haveCompleteStateHelper(
const rclcpp::Time& oldest_allowed_update_time,
204 std::vector<std::string>* missing_joints)
const
206 const std::vector<const moveit::core::JointModel*>& active_joints = robot_model_->getActiveJointModels();
207 std::unique_lock<std::mutex> slock(state_update_lock_);
210 std::map<const moveit::core::JointModel*, rclcpp::Time>::const_iterator it = joint_time_.find(joint);
211 if (it == joint_time_.end())
213 RCLCPP_DEBUG(LOGGER,
"Joint '%s' has never been updated", joint->getName().c_str());
215 else if (it->second < oldest_allowed_update_time)
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());
224 missing_joints->push_back(joint->getName());
228 return (missing_joints ==
nullptr) || missing_joints->empty();
233 rclcpp::Time start = middleware_handle_->now();
234 rclcpp::Duration elapsed(0, 0);
235 rclcpp::Duration timeout = rclcpp::Duration::from_seconds(wait_time_s);
237 rclcpp::Clock steady_clock(RCL_STEADY_TIME);
238 std::unique_lock<std::mutex> lock(state_update_lock_);
239 while (current_state_time_ < t)
243 if (state_update_condition_.wait_for(lock, 100ms) == std::cv_status::timeout)
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);
255 state_update_condition_.wait_for(lock, (timeout - elapsed).to_chrono<std::chrono::duration<double>>());
257 elapsed = middleware_handle_->now() - start;
258 if (elapsed > timeout)
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());
267 if (!middleware_handle_->ok())
269 RCLCPP_DEBUG(LOGGER,
"ROS context shut down while waiting for current robot state.");
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;
283 middleware_handle_->sleepFor(sleep_step_duration.to_chrono<std::chrono::nanoseconds>());
284 slept_time_s += sleep_step_s;
296 std::vector<std::string> missing_joints;
302 std::set<std::string> mj;
303 mj.insert(missing_joints.begin(), missing_joints.end());
306 for (std::size_t i = 0; ok && i < names.size(); ++i)
307 if (mj.find(names[i]) != mj.end())
316 void CurrentStateMonitor::jointStateCallback(
const sensor_msgs::msg::JointState::ConstSharedPtr& joint_state)
318 if (joint_state->name.size() != joint_state->position.size())
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 "
329 std::unique_lock<std::mutex> _(state_update_lock_);
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)
342 joint_time_.insert_or_assign(jm, joint_state->header.stamp);
369 if (joint_state->name.size() == joint_state->velocity.size() &&
377 if (joint_state->name.size() == joint_state->effort.size() &&
390 update_callback(joint_state);
393 state_update_condition_.notify_all();
396 void CurrentStateMonitor::updateMultiDofJoints()
399 const std::vector<const moveit::core::JointModel*>& multi_dof_joints = robot_model_->getMultiDOFJointModels();
402 bool changes =
false;
404 std::unique_lock<std::mutex> _(state_update_lock_);
407 const std::string& child_frame = joint->getChildLinkModel()->getName();
408 const std::string& parent_frame =
409 joint->getParentLinkModel() ? joint->getParentLinkModel()->getName() : robot_model_->getModelFrame();
411 rclcpp::Time latest_common_time(0, 0, RCL_ROS_TIME);
412 geometry_msgs::msg::TransformStamped transf;
415 transf = tf_buffer_->lookupTransform(parent_frame, child_frame, tf2::TimePointZero);
416 latest_common_time = transf.header.stamp;
418 catch (tf2::TransformException& ex)
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());
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));
432 if (latest_common_time <= joint_time_[joint] && latest_common_time > rclcpp::Time(0, 0, RCL_ROS_TIME))
434 joint_time_[joint] = latest_common_time;
436 std::vector<double> new_values(joint->getStateSpaceDimension());
439 joint->computeVariablePositions(tf2::transformToEigen(transf), new_values.data());
444 if (joint->distance(new_values.data(), robot_state_.
getJointPositions(joint)) > 1e-5)
459 auto joint_state = std::make_shared<sensor_msgs::msg::JointState>();
461 update_callback(joint_state);
467 state_update_condition_.notify_all();
472 void CurrentStateMonitor::transformCallback(
const tf2_msgs::msg::TFMessage::ConstSharedPtr& msg,
const bool is_static)
474 for (
const auto& transform : msg->transforms)
478 tf_buffer_->setTransform(transform,
479 is_static ? middleware_handle_->getStaticTfTopicName() :
480 middleware_handle_->getDynamicTfTopicName(),
483 catch (tf2::TransformException& ex)
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());
490 updateMultiDofJoints();
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.
bool jointOriginTransformIsIdentity() const
const Eigen::Isometry3d & getJointOriginTransform() const
When transforms are computed for this link, they are usually applied to the link's origin....
Representation of a robot's state. This includes position, velocity, acceleration and effort.
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)
const double * getJointEffort(const std::string &joint_name) const
const double * getJointPositions(const std::string &joint_name) const
bool hasVelocities() const
By default, if velocities are never set or initialized, the state remembers that there are no velocit...
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...
double * getVariablePositions()
Get a raw pointer to the positions of the variables stored in this state. Use carefully....
const double * getJointVelocities(const std::string &joint_name) const
bool hasEffort() const
By default, if effort is never set or initialized, the state remembers that there is no effort set....
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...
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 * getVariableAccelerations()
Get raw access to the accelerations of the variables that make up this state. The values are in the s...
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 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.
std::function< void(sensor_msgs::msg::JointState::ConstSharedPtr)> JointStateUpdateCallback
const rclcpp::Logger LOGGER