#include <RobotInfo.h>
Public Member Functions | |
sensor_msgs::JointState | getCurrentJointState (ros::NodeHandle &n) |
sensor_msgs::JointState | getCurrentJointState (const std::string &topicName, ros::NodeHandle &n) |
geometry_msgs::PoseStamped | getCurrentRobotPose (ros::NodeHandle &n) |
geometry_msgs::PoseStamped | getCurrentRobotPose (const std::string &topicName, ros::NodeHandle &n) |
geometry_msgs::PoseWithCovarianceStamped | getCurrentRobotPoseWithCovariance (ros::NodeHandle &n) |
geometry_msgs::PoseWithCovarianceStamped | getCurrentRobotPoseWithCovariance (const std::string &topicName, ros::NodeHandle &n) |
sensor_msgs::MultiDOFJointState | getCurrentVirtualJointState (const std::string &poseTopicName, ros::NodeHandle &n, const std::string &virtualJointName, const std::string &frameID) |
RobotInfo (const std::string &default_robot_pose_topic="/amcl_pose", const std::string &default_joint_states_topic="/joint_states") | |
~RobotInfo () | |
Static Public Member Functions | |
static sensor_msgs::MultiDOFJointState | getVirtualJointState (const geometry_msgs::PoseStamped &robotPose, const std::string &virtualJointName, const std::string &frameID) |
Private Types | |
typedef baselib_binding::mutex | mutex |
typedef baselib_binding::unique_lock < mutex >::type | unique_lock |
Private Member Functions | |
void | jointStateCallback (const sensor_msgs::JointState &jointstate) |
void | poseCallback (const geometry_msgs::PoseWithCovarianceStamped &msg) |
bool | receivedJointState () |
bool | receivedRobotPose () |
Private Attributes | |
std::string | joint_states_topic |
sensor_msgs::JointState | jointState |
mutex | jointStateMutex |
geometry_msgs::PoseWithCovarianceStamped | pose |
mutex | poseMutex |
bool | received_js |
bool | received_rp |
std::string | robot_pose_topic |
A helper class which includes convenience function to access the most recent information of the robot state. This class is not continuously subscribed to topics. The subscribers are launched on-demand, so it is suitable if you only need the states now and then, and not continuously.
Definition at line 22 of file RobotInfo.h.
typedef baselib_binding::mutex convenience_ros_functions::RobotInfo::mutex [private] |
Definition at line 63 of file RobotInfo.h.
typedef baselib_binding::unique_lock<mutex>::type convenience_ros_functions::RobotInfo::unique_lock [private] |
Definition at line 64 of file RobotInfo.h.
RobotInfo::RobotInfo | ( | const std::string & | default_robot_pose_topic = "/amcl_pose" , |
const std::string & | default_joint_states_topic = "/joint_states" |
||
) |
default_robot_pose_topic | the default robot pose topic. This allows convenience functions to be called without specifying the topic every time. |
default_joint_states_topic | the default joint states topic. This allows convenience functions to be called without specifying the topic every time. |
Definition at line 7 of file RobotInfo.cpp.
Definition at line 13 of file RobotInfo.cpp.
sensor_msgs::JointState RobotInfo::getCurrentJointState | ( | ros::NodeHandle & | n | ) |
Definition at line 74 of file RobotInfo.cpp.
sensor_msgs::JointState RobotInfo::getCurrentJointState | ( | const std::string & | topicName, |
ros::NodeHandle & | n | ||
) |
Definition at line 52 of file RobotInfo.cpp.
geometry_msgs::PoseStamped RobotInfo::getCurrentRobotPose | ( | ros::NodeHandle & | n | ) |
Definition at line 15 of file RobotInfo.cpp.
geometry_msgs::PoseStamped RobotInfo::getCurrentRobotPose | ( | const std::string & | topicName, |
ros::NodeHandle & | n | ||
) |
Definition at line 19 of file RobotInfo.cpp.
geometry_msgs::PoseWithCovarianceStamped RobotInfo::getCurrentRobotPoseWithCovariance | ( | ros::NodeHandle & | n | ) |
Definition at line 48 of file RobotInfo.cpp.
geometry_msgs::PoseWithCovarianceStamped RobotInfo::getCurrentRobotPoseWithCovariance | ( | const std::string & | topicName, |
ros::NodeHandle & | n | ||
) |
Definition at line 27 of file RobotInfo.cpp.
sensor_msgs::MultiDOFJointState RobotInfo::getCurrentVirtualJointState | ( | const std::string & | poseTopicName, |
ros::NodeHandle & | n, | ||
const std::string & | virtualJointName, | ||
const std::string & | frameID | ||
) |
get the current robot pose, and get it as a MulitDOFJointState, transformed to the most recent transform available in frame_id
Definition at line 118 of file RobotInfo.cpp.
sensor_msgs::MultiDOFJointState RobotInfo::getVirtualJointState | ( | const geometry_msgs::PoseStamped & | robotPose, |
const std::string & | virtualJointName, | ||
const std::string & | frameID | ||
) | [static] |
Transforms the robotPose into frameID and then constructs a sensor_msgs::MultiDOFJointState using this transformed pose.
Background info: MoveIt likes to have the MultiDOFJointState in the frame specified at configuration time (e.g. odom) and seems to have trouble converting it. So do it here. If this frame changes, pass it into "frame_id" parameter.
Definition at line 80 of file RobotInfo.cpp.
void RobotInfo::jointStateCallback | ( | const sensor_msgs::JointState & | jointstate | ) | [private] |
Definition at line 129 of file RobotInfo.cpp.
void RobotInfo::poseCallback | ( | const geometry_msgs::PoseWithCovarianceStamped & | msg | ) | [private] |
Definition at line 140 of file RobotInfo.cpp.
bool RobotInfo::receivedJointState | ( | ) | [private] |
Definition at line 124 of file RobotInfo.cpp.
bool RobotInfo::receivedRobotPose | ( | ) | [private] |
Definition at line 135 of file RobotInfo.cpp.
std::string convenience_ros_functions::RobotInfo::joint_states_topic [private] |
Definition at line 80 of file RobotInfo.h.
sensor_msgs::JointState convenience_ros_functions::RobotInfo::jointState [private] |
Definition at line 76 of file RobotInfo.h.
Definition at line 75 of file RobotInfo.h.
geometry_msgs::PoseWithCovarianceStamped convenience_ros_functions::RobotInfo::pose [private] |
Definition at line 73 of file RobotInfo.h.
Definition at line 71 of file RobotInfo.h.
bool convenience_ros_functions::RobotInfo::received_js [private] |
Definition at line 77 of file RobotInfo.h.
bool convenience_ros_functions::RobotInfo::received_rp [private] |
Definition at line 72 of file RobotInfo.h.
std::string convenience_ros_functions::RobotInfo::robot_pose_topic [private] |
Definition at line 79 of file RobotInfo.h.