#include <self_mask_urdf_robot.h>
|
void | assumeFrameFromJointAngle (const sensor_msgs::JointState &joint, const geometry_msgs::PoseStamped &pose) |
|
bool | initKdlConfigure () |
|
| SelfMaskUrdfRobot (tf::TransformListener &tfl, tf::TransformBroadcaster &tfb, const std::vector< LinkInfo > &links, const urdf::Model &urdf_model, std::string root_link_id="BODY", std::string world_frame_id="map", bool set_foot_pose=false) |
|
void | updateChain (std::map< std::string, double > &joint_angles, KDL::Chain &chain, tf::Pose &output_pose) |
|
void | updateRobotModel (std::map< std::string, double > &joint_angles, const tf::Pose &root_pose) |
|
Definition at line 17 of file self_mask_urdf_robot.h.
void robot_self_filter::SelfMaskUrdfRobot::assumeFrameFromJointAngle |
( |
const sensor_msgs::JointState & |
joint, |
|
|
const geometry_msgs::PoseStamped & |
pose |
|
) |
| |
|
inline |
bool robot_self_filter::SelfMaskUrdfRobot::initKdlConfigure |
( |
| ) |
|
|
inline |
void robot_self_filter::SelfMaskUrdfRobot::updateChain |
( |
std::map< std::string, double > & |
joint_angles, |
|
|
KDL::Chain & |
chain, |
|
|
tf::Pose & |
output_pose |
|
) |
| |
|
inline |
void robot_self_filter::SelfMaskUrdfRobot::updateRobotModel |
( |
std::map< std::string, double > & |
joint_angles, |
|
|
const tf::Pose & |
root_pose |
|
) |
| |
|
inline |
bool robot_self_filter::SelfMaskUrdfRobot::publish_tf_ |
|
protected |
std::string robot_self_filter::SelfMaskUrdfRobot::root_link_id_ |
|
protected |
KDL::Tree robot_self_filter::SelfMaskUrdfRobot::tree_ |
|
protected |
urdf::Model robot_self_filter::SelfMaskUrdfRobot::urdf_model_ |
|
protected |
std::string robot_self_filter::SelfMaskUrdfRobot::world_frame_id_ |
|
protected |
The documentation for this class was generated from the following file: