71 robot_state::RobotState* result =
new robot_state::RobotState(
robot_state_);
72 return robot_state::RobotStatePtr(result);
81 std::pair<robot_state::RobotStatePtr, ros::Time>
85 robot_state::RobotState* result =
new robot_state::RobotState(
robot_state_);
91 std::map<std::string, double> m;
94 const std::vector<std::string>& names =
robot_state_.getVariableNames();
95 for (std::size_t i = 0; i < names.size(); ++i)
103 const double* pos =
robot_state_.getVariablePositions();
104 upd.setVariablePositions(pos);
109 const double* vel =
robot_state_.getVariableVelocities();
110 upd.setVariableVelocities(vel);
114 const double* acc =
robot_state_.getVariableAccelerations();
115 upd.setVariableAccelerations(acc);
120 upd.setVariableEffort(eff);
141 if (joint_states_topic.empty())
142 ROS_ERROR(
"The joint states topic cannot be an empty string");
171 ROS_DEBUG(
"No longer listening for joint states");
187 const std::vector<const moveit::core::JointModel*>& joints =
robot_model_->getActiveJointModels();
192 if (!joint->isPassive() && !joint->getMimic())
194 ROS_DEBUG(
"Joint '%s' has never been updated", joint->getName().c_str());
204 const std::vector<const moveit::core::JointModel*>& joints =
robot_model_->getActiveJointModels();
208 if (!joint->isPassive() && !joint->getMimic())
210 missing_states.push_back(joint->getName());
219 const std::vector<const moveit::core::JointModel*>& joints =
robot_model_->getActiveJointModels();
225 if (joint->isPassive() || joint->getMimic())
227 std::map<const moveit::core::JointModel*, ros::Time>::const_iterator it =
joint_time_.find(joint);
230 ROS_DEBUG(
"Joint '%s' has never been updated", joint->getName().c_str());
233 else if (it->second < old)
235 ROS_DEBUG(
"Joint '%s' was last updated %0.3lf seconds ago (older than the allowed %0.3lf seconds)",
236 joint->getName().c_str(), (now - it->second).toSec(), age.toSec());
244 std::vector<std::string>& missing_states)
const 247 const std::vector<const moveit::core::JointModel*>& joints =
robot_model_->getActiveJointModels();
253 if (joint->isPassive() || joint->getMimic())
255 std::map<const moveit::core::JointModel*, ros::Time>::const_iterator it =
joint_time_.find(joint);
258 ROS_DEBUG(
"Joint '%s' has never been updated", joint->getName().c_str());
259 missing_states.push_back(joint->getName());
262 else if (it->second < old)
264 ROS_DEBUG(
"Joint '%s' was last updated %0.3lf seconds ago (older than the allowed %0.3lf seconds)",
265 joint->getName().c_str(), (now - it->second).toSec(), age.toSec());
266 missing_states.push_back(joint->getName());
284 if (elapsed > timeout)
286 ROS_INFO_STREAM(
"Didn't received robot state (joint angles) with recent timestamp within " 287 << wait_time <<
" seconds.\n" 288 <<
"Check clock synchronization if your are running ROS across multiple machines!");
297 double slept_time = 0.0;
298 double sleep_step_s = std::min(0.05, wait_time / 10.0);
303 slept_time += sleep_step_s;
319 std::vector<std::string> missing_joints;
325 std::set<std::string> mj;
326 mj.insert(missing_joints.begin(), missing_joints.end());
329 for (std::size_t i = 0; ok && i < names.size(); ++i)
330 if (mj.find(names[i]) != mj.end())
346 if (joint_state->name.size() != joint_state->position.size())
348 ROS_ERROR_THROTTLE(1,
"State monitor received invalid joint state (number of joint names does not match number of " 357 std::size_t n = joint_state->name.size();
359 for (std::size_t i = 0; i < n; ++i)
370 if (
robot_state_.getJointPositions(jm)[0] != joint_state->position[i])
373 robot_state_.setJointPositions(jm, &(joint_state->position[i]));
379 if (joint_state->name.size() == joint_state->velocity.size())
381 robot_state_.setJointVelocities(jm, &(joint_state->velocity[i]));
384 if (joint_state->name.size() == joint_state->effort.size())
386 robot_state_.setJointEfforts(jm, &(joint_state->effort[i]));
393 if (static_cast<const moveit::core::RevoluteJointModel*>(jm)->isContinuous())
396 const robot_model::VariableBounds& b =
401 if (joint_state->position[i] < b.min_position_ && joint_state->position[i] >= b.min_position_ -
error_)
403 else if (joint_state->position[i] > b.max_position_ && joint_state->position[i] <= b.max_position_ +
error_)
421 const std::vector<const moveit::core::JointModel*>& multi_dof_joints =
robot_model_->getMultiDOFJointModels();
424 bool changes =
false;
428 for (
size_t i = 0; i < multi_dof_joints.size(); i++)
432 const std::string& parent_frame =
437 if (
tf_->getLatestCommonTime(parent_frame, child_frame, latest_common_time, &err) !=
tf::NO_ERROR)
440 << joint->
getName() <<
"': TF has no common time between '" << parent_frame.c_str()
441 <<
"' and '" << child_frame.c_str() <<
"': " << err);
452 tf_->lookupTransform(parent_frame, child_frame, latest_common_time, transf);
457 <<
"'. TF exception: " << ex.what());
462 Eigen::Affine3d eigen_transf;
467 if (link->jointOriginTransformIsIdentity())
488 sensor_msgs::JointStatePtr joint_state(
new sensor_msgs::JointState);
const std::string & getName() const
const std::string & getName() const
std::size_t getVariableCount() const
void stopStateMonitor()
Stop monitoring the "joint_states" topic.
bool state_monitor_started_
boost::shared_ptr< tf::Transformer > tf_
void setToCurrentState(robot_state::RobotState &upd) const
Set the state upd to the current state maintained by this class.
CurrentStateMonitor(const robot_model::RobotModelConstPtr &robot_model, const boost::shared_ptr< tf::Transformer > &tf)
Constructor.
decltype(tf::Transformer().addTransformsChangedListener(boost::function< void(void)>())) typedef TFConnection
boost::mutex state_update_lock_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::map< const moveit::core::JointModel *, ros::Time > joint_time_
std::string resolveName(const std::string &name, bool remap=true) const
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...
Monitors the joint_states topic and tf to maintain the current state of the robot.
robot_model::RobotModelConstPtr robot_model_
std::map< std::string, double > getCurrentStateValues() const
Get the current state values as a map from joint names to joint state values.
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
void startStateMonitor(const std::string &joint_states_topic="joint_states")
Start monitoring joint states on a particular topic.
std::pair< robot_state::RobotStatePtr, ros::Time > getCurrentStateAndTime() const
Get the current state and its time stamp.
#define ROS_ERROR_THROTTLE(rate,...)
boost::condition_variable state_update_condition_
std::string getMonitoredTopic() const
Get the name of the topic being monitored. Returns an empty string if the monitor is inactive...
virtual double distance(const double *value1, const double *value2) const =0
std::vector< JointStateUpdateCallback > update_callbacks_
ros::Time current_state_time_
robot_state::RobotState robot_state_
void jointStateCallback(const sensor_msgs::JointStateConstPtr &joint_state)
std::string getTopic() const
const std::vector< std::string > & getJointModelNames() const
std::shared_ptr< TFConnection > tf_connection_
ros::Subscriber joint_state_subscriber_
bool waitForCompleteState(double wait_time) const
Wait for at most wait_time seconds until the complete robot state is known.
#define ROS_INFO_STREAM(args)
const LinkModel * getChildLinkModel() const
bool haveCompleteState() const
Query whether we have joint state information for all DOFs in the kinematic model.
#define ROS_WARN_STREAM_ONCE(args)
void clearUpdateCallbacks()
Clear the functions to be called when an update to the joint state is received.
const LinkModel * getParentLinkModel() const
void transformTFToEigen(const tf::Transform &t, Eigen::Isometry3d &e)
boost::function< void(const sensor_msgs::JointStateConstPtr &joint_state)> JointStateUpdateCallback
#define ROS_ERROR_STREAM_THROTTLE(rate, args)
const VariableBounds & getVariableBounds(const std::string &variable) const
ros::Time monitor_start_time_
ros::Time getCurrentStateTime() const
Get the time stamp for the current state.
JointType getType() const
virtual void computeVariablePositions(const Eigen::Affine3d &transform, double *joint_values) const =0
void addUpdateCallback(const JointStateUpdateCallback &fn)
Add a function that will be called whenever the joint state is updated.
virtual unsigned int getStateSpaceDimension() const =0
bool isActive() const
Check if the state monitor is started.
robot_state::RobotStatePtr getCurrentState() const
Get the current state.