Go to the documentation of this file.
   42 #include <sensor_msgs/JointState.h> 
   43 #include <boost/function.hpp> 
   44 #include <boost/thread/mutex.hpp> 
   45 #include <boost/thread/condition_variable.hpp> 
   63                       const std::shared_ptr<tf2_ros::Buffer>& 
tf_buffer);
 
  127   inline bool haveCompleteState(std::vector<std::string>& missing_joints, 
const std::string& group = 
"")
 const 
  138                                 const std::string& group = 
"")
 const 
  148                                 const std::string& group = 
"")
 const 
  174   std::pair<moveit::core::RobotStatePtr, ros::Time> 
getCurrentStateAndTime(
const std::string& group = 
"") 
const;
 
  211     error_ = (error > 0) ? error : -error;
 
  237                                const std::string& group) 
const;
 
  246   std::map<const moveit::core::JointModel*, ros::Time> 
joint_time_;
 
  
moveit::core::RobotModelConstPtr robot_model_
ros::Time getCurrentStateTimeHelper(const std::string &group="") const
void stopStateMonitor()
Stop monitoring the "joint_states" topic.
std::map< const moveit::core::JointModel *, ros::Time > joint_time_
const moveit::core::RobotModelConstPtr & getRobotModel() const
Get the RobotModel for which we are monitoring state.
boost::mutex state_update_lock_
bool isActive() const
Check if the state monitor is started.
bool haveCompleteStateHelper(const ros::Time &oldest_allowed_update_time, std::vector< std::string > *missing_joints, const std::string &group) const
CurrentStateMonitor(const moveit::core::RobotModelConstPtr &robot_model, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer)
Constructor.
void setBoundsError(double error)
When a joint value is received to be out of bounds, it is changed slightly to fit within bounds,...
boost::function< void(const sensor_msgs::JointStateConstPtr &)> JointStateUpdateCallback
void startStateMonitor(const std::string &joint_states_topic="joint_states")
Start monitoring joint states on a particular topic.
void enableCopyDynamics(bool enabled)
Allow the joint_state arrrays velocity and effort to be copied into the robot state this is useful in...
boost::condition_variable state_update_condition_
double getBoundsError() const
When a joint value is received to be out of bounds, it is changed slightly to fit within bounds,...
std::vector< JointStateUpdateCallback > update_callbacks_
void jointStateCallback(const sensor_msgs::JointStateConstPtr &joint_state)
void setToCurrentState(moveit::core::RobotState &upd) const
Set the state upd to the current state maintained by this class.
bool haveCompleteState(const std::string &group="") const
Query whether we have joint state information for all DOFs in the kinematic model.
bool waitForCurrentState(const ros::Time t=ros::Time::now(), double wait_time=1.0) const
Wait for at most wait_time seconds (default 1s) for a robot state more recent than t.
boost::signals2::connection TFConnection
MOVEIT_CLASS_FORWARD(CurrentStateMonitor)
std::shared_ptr< TFConnection > tf_connection_
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
ros::Subscriber joint_state_subscriber_
tf2_ros::Buffer * tf_buffer
bool waitForCompleteState(double wait_time) const
Wait for at most wait_time seconds until the complete robot state is known.
moveit::core::RobotStatePtr getCurrentState() const
Get the current state.
std::map< std::string, double > getCurrentStateValues() const
Get the current state values as a map from joint names to joint state values.
moveit::core::RobotState robot_state_
void clearUpdateCallbacks()
Clear the functions to be called when an update to the joint state is received.
std::pair< moveit::core::RobotStatePtr, ros::Time > getCurrentStateAndTime(const std::string &group="") const
Get the current state and its time stamp.
ros::Time getCurrentStateTime(const std::string &group="") const
Get the time stamp for the current state.
ros::Time monitor_start_time_
const ros::Time & getMonitorStartTime() const
Get the time point when the monitor was started.
std::string getMonitoredTopic() const
Get the name of the topic being monitored. Returns an empty string if the monitor is inactive.
bool state_monitor_started_
void addUpdateCallback(const JointStateUpdateCallback &fn)
Add a function that will be called whenever the joint state is updated.
planning
Author(s): Ioan Sucan 
, Sachin Chitta 
autogenerated on Sat May 3 2025 02:26:19