#include <base_kinematics.h>
Public Member Functions | |
| bool | init (pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &node, std::string link_name) |
| Loads wheel's information from the xml description file and param server. | |
| void | updatePosition () |
| Computes 2d postion of the wheel relative to the center of the base. | |
Public Attributes | |
| int | direction_multiplier_ |
| specifies the default direction of the wheel | |
| pr2_mechanism_model::JointState * | joint_ |
| JointState for this wheel joint. | |
| std::string | joint_name_ |
| name of the joint | |
| std::string | link_name_ |
| name of the link | |
| geometry_msgs::Point | offset_ |
| default offset from the parent caster before any transformations | |
| Caster * | parent_ |
| the caster on which this wheel is mounted | |
| geometry_msgs::Point | position_ |
| offset_ after rotation transformation from the parent caster's position | |
| double | wheel_radius_ |
| wheel radius scale (based on the default wheel radius in Basekinematics) | |
| double | wheel_speed_actual_ |
| actual wheel speeds | |
| double | wheel_speed_cmd_ |
| desired wheel speed | |
| double | wheel_speed_error_ |
| difference between desired and actual speed | |
| double | wheel_speed_filtered_ |
| wheel speed filtered with alpha | |
| int | wheel_stuck_ |
| remembers if the wheel is stalled | |
Definition at line 56 of file base_kinematics.h.
| bool Wheel::init | ( | pr2_mechanism_model::RobotState * | robot_state, |
| ros::NodeHandle & | node, | ||
| std::string | link_name | ||
| ) |
Loads wheel's information from the xml description file and param server.
| robot_state | The robot's current state |
| config | Tiny xml element pointing to this wheel |
Definition at line 44 of file base_kinematics.cpp.
| void Wheel::updatePosition | ( | ) |
Computes 2d postion of the wheel relative to the center of the base.
Definition at line 195 of file base_kinematics.cpp.
specifies the default direction of the wheel
Definition at line 114 of file base_kinematics.h.
JointState for this wheel joint.
Definition at line 63 of file base_kinematics.h.
| std::string controller::Wheel::joint_name_ |
name of the joint
Definition at line 73 of file base_kinematics.h.
| std::string controller::Wheel::link_name_ |
name of the link
Definition at line 78 of file base_kinematics.h.
default offset from the parent caster before any transformations
Definition at line 68 of file base_kinematics.h.
the caster on which this wheel is mounted
Definition at line 89 of file base_kinematics.h.
offset_ after rotation transformation from the parent caster's position
Definition at line 84 of file base_kinematics.h.
wheel radius scale (based on the default wheel radius in Basekinematics)
Definition at line 124 of file base_kinematics.h.
actual wheel speeds
Definition at line 94 of file base_kinematics.h.
desired wheel speed
Definition at line 99 of file base_kinematics.h.
difference between desired and actual speed
Definition at line 104 of file base_kinematics.h.
wheel speed filtered with alpha
Definition at line 109 of file base_kinematics.h.
remembers if the wheel is stalled
Definition at line 119 of file base_kinematics.h.