42 #include <condition_variable>
45 #include <boost/signals2.hpp>
47 #include <rclcpp/rclcpp.hpp>
48 #include <sensor_msgs/msg/joint_state.hpp>
49 #include <tf2_msgs/msg/tf_message.hpp>
51 #include <tf2_ros/buffer.h>
70 using TfCallback = std::function<void(
const tf2_msgs::msg::TFMessage::ConstSharedPtr)>;
82 virtual rclcpp::Time
now()
const = 0;
125 virtual bool sleepFor(
const std::chrono::nanoseconds& nanoseconds)
const = 0;
132 virtual bool ok()
const = 0;
161 const moveit::core::RobotModelConstPtr& robot_model,
162 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
bool use_sim_time);
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);
201 return haveCompleteStateHelper(rclcpp::Time(0, 0, RCL_ROS_TIME),
nullptr);
210 return haveCompleteStateHelper(oldest_allowed_update_time,
nullptr);
220 return haveCompleteStateHelper(middleware_handle_->now() - age,
nullptr);
229 return haveCompleteStateHelper(rclcpp::Time(0, 0, RCL_ROS_TIME), &missing_joints);
238 std::vector<std::string>& missing_joints)
const
240 return haveCompleteStateHelper(oldest_allowed_update_time, &missing_joints);
247 inline bool haveCompleteState(
const rclcpp::Duration& age, std::vector<std::string>& missing_joints)
const
249 return haveCompleteStateHelper(middleware_handle_->now() - age, &missing_joints);
273 bool waitForCurrentState(
const rclcpp::Time& t = rclcpp::Clock(RCL_ROS_TIME).now(),
double wait_time_s = 1.0)
const;
286 return monitor_start_time_;
301 error_ = (error > 0) ? error : -error;
318 copy_dynamics_ = enabled;
322 bool haveCompleteStateHelper(
const rclcpp::Time& oldest_allowed_update_time,
323 std::vector<std::string>* missing_joints)
const;
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);
329 std::unique_ptr<MiddlewareHandle> middleware_handle_;
330 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
331 moveit::core::RobotModelConstPtr robot_model_;
333 std::map<const moveit::core::JointModel*, rclcpp::Time> joint_time_;
334 bool state_monitor_started_;
336 rclcpp::Time monitor_start_time_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
338 rclcpp::Time current_state_time_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
340 mutable std::mutex state_update_lock_;
341 mutable std::condition_variable state_update_condition_;
342 std::vector<JointStateUpdateCallback> update_callbacks_;
Representation of a robot's state. This includes position, velocity, acceleration and effort.
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)