moveit2
The MoveIt Motion Planning Framework for ROS 2.
current_state_monitor.h
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 
37 #pragma once
38 
39 #include <chrono>
40 #include <functional>
41 #include <string>
42 #include <condition_variable>
43 #include <mutex>
44 
45 #include <boost/signals2.hpp>
46 
47 #include <rclcpp/rclcpp.hpp>
48 #include <sensor_msgs/msg/joint_state.hpp>
49 #include <tf2_msgs/msg/tf_message.hpp>
50 
51 #include <tf2_ros/buffer.h>
52 
54 
55 namespace planning_scene_monitor
56 {
57 using JointStateUpdateCallback = std::function<void(sensor_msgs::msg::JointState::ConstSharedPtr)>;
58 
62 {
63 public:
68  {
69  public:
70  using TfCallback = std::function<void(const tf2_msgs::msg::TFMessage::ConstSharedPtr)>;
71 
75  virtual ~MiddlewareHandle() = default;
76 
82  virtual rclcpp::Time now() const = 0;
83 
90  virtual void createJointStateSubscription(const std::string& topic, JointStateUpdateCallback callback) = 0;
91 
97  virtual void createStaticTfSubscription(TfCallback callback) = 0;
98 
104  virtual void createDynamicTfSubscription(TfCallback callback) = 0;
105 
109  virtual void resetJointStateSubscription() = 0;
110 
116  virtual std::string getJointStateTopicName() const = 0;
117 
125  virtual bool sleepFor(const std::chrono::nanoseconds& nanoseconds) const = 0;
126 
132  virtual bool ok() const = 0;
133 
139  virtual std::string getStaticTfTopicName() const = 0;
140 
146  virtual std::string getDynamicTfTopicName() const = 0;
147 
151  virtual void resetTfSubscriptions() = 0;
152  };
153 
160  CurrentStateMonitor(std::unique_ptr<MiddlewareHandle> middleware_handle,
161  const moveit::core::RobotModelConstPtr& robot_model,
162  const std::shared_ptr<tf2_ros::Buffer>& tf_buffer, bool use_sim_time);
163 
170  CurrentStateMonitor(const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModelConstPtr& robot_model,
171  const std::shared_ptr<tf2_ros::Buffer>& tf_buffer, bool use_sim_time);
172 
174 
178  void startStateMonitor(const std::string& joint_states_topic = "joint_states");
179 
182  void stopStateMonitor();
183 
185  bool isActive() const;
186 
188  const moveit::core::RobotModelConstPtr& getRobotModel() const
189  {
190  return robot_model_;
191  }
192 
194  std::string getMonitoredTopic() const;
195 
199  inline bool haveCompleteState() const
200  {
201  return haveCompleteStateHelper(rclcpp::Time(0, 0, RCL_ROS_TIME), nullptr);
202  }
203 
208  inline bool haveCompleteState(const rclcpp::Time& oldest_allowed_update_time) const
209  {
210  return haveCompleteStateHelper(oldest_allowed_update_time, nullptr);
211  }
212 
218  inline bool haveCompleteState(const rclcpp::Duration& age) const
219  {
220  return haveCompleteStateHelper(middleware_handle_->now() - age, nullptr);
221  }
222 
227  inline bool haveCompleteState(std::vector<std::string>& missing_joints) const
228  {
229  return haveCompleteStateHelper(rclcpp::Time(0, 0, RCL_ROS_TIME), &missing_joints);
230  }
231 
237  inline bool haveCompleteState(const rclcpp::Time& oldest_allowed_update_time,
238  std::vector<std::string>& missing_joints) const
239  {
240  return haveCompleteStateHelper(oldest_allowed_update_time, &missing_joints);
241  }
242 
247  inline bool haveCompleteState(const rclcpp::Duration& age, std::vector<std::string>& missing_joints) const
248  {
249  return haveCompleteStateHelper(middleware_handle_->now() - age, &missing_joints);
250  }
251 
254  moveit::core::RobotStatePtr getCurrentState() const;
255 
258 
260  rclcpp::Time getCurrentStateTime() const;
261 
264  std::pair<moveit::core::RobotStatePtr, rclcpp::Time> getCurrentStateAndTime() const;
265 
268  std::map<std::string, double> getCurrentStateValues() const;
269 
273  bool waitForCurrentState(const rclcpp::Time& t = rclcpp::Clock(RCL_ROS_TIME).now(), double wait_time_s = 1.0) const;
274 
277  bool waitForCompleteState(double wait_time_s) const;
278 
281  bool waitForCompleteState(const std::string& group, double wait_time_s) const;
282 
284  const rclcpp::Time& getMonitorStartTime() const
285  {
286  return monitor_start_time_;
287  }
288 
291 
293  void clearUpdateCallbacks();
294 
299  void setBoundsError(double error)
300  {
301  error_ = (error > 0) ? error : -error;
302  }
303 
308  double getBoundsError() const
309  {
310  return error_;
311  }
312 
316  void enableCopyDynamics(bool enabled)
317  {
318  copy_dynamics_ = enabled;
319  }
320 
321 private:
322  bool haveCompleteStateHelper(const rclcpp::Time& oldest_allowed_update_time,
323  std::vector<std::string>* missing_joints) const;
324 
325  void jointStateCallback(const sensor_msgs::msg::JointState::ConstSharedPtr& joint_state);
326  void updateMultiDofJoints();
327  void transformCallback(const tf2_msgs::msg::TFMessage::ConstSharedPtr& msg, const bool is_static);
328 
329  std::unique_ptr<MiddlewareHandle> middleware_handle_;
330  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
331  moveit::core::RobotModelConstPtr robot_model_;
332  moveit::core::RobotState robot_state_;
333  std::map<const moveit::core::JointModel*, rclcpp::Time> joint_time_;
334  bool state_monitor_started_;
335  bool copy_dynamics_; // Copy velocity and effort from joint_state
336  rclcpp::Time monitor_start_time_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
337  double error_;
338  rclcpp::Time current_state_time_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
339 
340  mutable std::mutex state_update_lock_;
341  mutable std::condition_variable state_update_condition_;
342  std::vector<JointStateUpdateCallback> update_callbacks_;
343 
344  bool use_sim_time_;
345 };
346 
347 MOVEIT_CLASS_FORWARD(CurrentStateMonitor); // Defines CurrentStateMonitorPtr, ConstPtr, WeakPtr... etc
348 } // namespace planning_scene_monitor
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
Dependency injection class for testing the CurrentStateMonitor.
virtual std::string getJointStateTopicName() const =0
Get the joint state topic name.
virtual void createStaticTfSubscription(TfCallback callback)=0
Creates a static transform message subscription.
virtual void resetTfSubscriptions()=0
Reset the static & dynamic transform subscriptions.
virtual void resetJointStateSubscription()=0
Reset the joint state subscription.
virtual bool sleepFor(const std::chrono::nanoseconds &nanoseconds) const =0
Block for the specified amount of time.
virtual void createJointStateSubscription(const std::string &topic, JointStateUpdateCallback callback)=0
Creates a joint state subscription.
virtual ~MiddlewareHandle()=default
Destroys the object.
std::function< void(const tf2_msgs::msg::TFMessage::ConstSharedPtr)> TfCallback
virtual std::string getDynamicTfTopicName() const =0
Get the dynamic transform topic name.
virtual rclcpp::Time now() const =0
Get the current time.
virtual void createDynamicTfSubscription(TfCallback callback)=0
Creates a dynamic transform message subscription.
virtual bool ok() const =0
Uses rclcpp::ok to check the context status.
virtual std::string getStaticTfTopicName() const =0
Get the static transform topic name.
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.
bool haveCompleteState(std::vector< std::string > &missing_joints) const
Query whether we have joint state information for all DOFs in the kinematic model.
double getBoundsError() const
When a joint value is received to be out of bounds, it is changed slightly to fit within bounds,...
void setToCurrentState(moveit::core::RobotState &upd) const
Set the state upd to the current state maintained by this class.
const moveit::core::RobotModelConstPtr & getRobotModel() const
Get the RobotModel for which we are monitoring state.
bool haveCompleteState(const rclcpp::Time &oldest_allowed_update_time, std::vector< std::string > &missing_joints) const
Query whether we have joint state information for all DOFs in the kinematic model.
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.
bool haveCompleteState(const rclcpp::Duration &age) const
Query whether we have joint state information for all DOFs in the kinematic model.
void setBoundsError(double error)
When a joint value is received to be out of bounds, it is changed slightly to fit within bounds,...
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.
bool haveCompleteState(const rclcpp::Duration &age, std::vector< std::string > &missing_joints) const
Query whether we have joint state information for all DOFs in the kinematic model.
void stopStateMonitor()
Stop monitoring the "joint_states" topic.
void enableCopyDynamics(bool enabled)
Allow the joint_state arrays velocity and effort to be copied into the robot state this is useful in ...
const rclcpp::Time & getMonitorStartTime() const
Get the time point when the monitor was started.
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.
bool haveCompleteState(const rclcpp::Time &oldest_allowed_update_time) const
Query whether we have joint state information for all DOFs in the kinematic model.
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
MOVEIT_CLASS_FORWARD(PlanningSceneMonitor)