#include <base_kinematics.h>
| Public Member Functions | |
| void | computeWheelPositions () | 
| Computes 2d postion of every wheel relative to the center of the base. | |
| bool | init (pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &node) | 
| Loads BaseKinematic's information from the xml description file and param server. | |
| geometry_msgs::Twist | pointVel2D (const geometry_msgs::Point &pos, const geometry_msgs::Twist &vel) | 
| Computes 2d velocity of a point at relative distance pos to another point with velocity (and rotation (z)) vel. | |
| Public Attributes | |
| std::vector< Caster > | caster_ | 
| vector of every caster attached to the base | |
| double | MAX_DT_ | 
| maximum dT used in computation of interpolated velocity command | |
| std::string | name_ | 
| name of this BaseKinematics (generally associated with whatever controller is using it) | |
| int | num_casters_ | 
| number of casters connected to the base | |
| int | num_wheels_ | 
| number of wheels connected to the base | |
| std::string | robot_base_id_ | 
| Name(string id) of the robot base frame. | |
| pr2_mechanism_model::RobotState * | robot_state_ | 
| remembers everything about the state of the robot | |
| std::vector< Wheel > | wheel_ | 
| vector of every wheel attached to the base | |
| std::string | xml_caster_name_ | 
| the name of the casters in the xml file | |
| std::string | xml_wheel_name_ | 
| the name of the wheels in the xml file | |
Definition at line 229 of file base_kinematics.h.
Computes 2d postion of every wheel relative to the center of the base.
Definition at line 206 of file base_kinematics.cpp.
| bool BaseKinematics::init | ( | pr2_mechanism_model::RobotState * | robot_state, | 
| ros::NodeHandle & | node | ||
| ) | 
Loads BaseKinematic's information from the xml description file and param server.
| robot_state | The robot's current state | 
| config | Tiny xml element pointing to its controller | 
Definition at line 144 of file base_kinematics.cpp.
| geometry_msgs::Twist BaseKinematics::pointVel2D | ( | const geometry_msgs::Point & | pos, | 
| const geometry_msgs::Twist & | vel | ||
| ) | 
Computes 2d velocity of a point at relative distance pos to another point with velocity (and rotation (z)) vel.
| pos | The position of the object relative to the center of rotation | 
| vel | Velocity of the center of rotation | 
Definition at line 215 of file base_kinematics.cpp.
vector of every caster attached to the base
Definition at line 277 of file base_kinematics.h.
maximum dT used in computation of interpolated velocity command
Definition at line 297 of file base_kinematics.h.
| std::string controller::BaseKinematics::name_ | 
name of this BaseKinematics (generally associated with whatever controller is using it)
Definition at line 292 of file base_kinematics.h.
number of casters connected to the base
Definition at line 267 of file base_kinematics.h.
number of wheels connected to the base
Definition at line 262 of file base_kinematics.h.
| std::string controller::BaseKinematics::robot_base_id_ | 
Name(string id) of the robot base frame.
Definition at line 302 of file base_kinematics.h.
remembers everything about the state of the robot
Definition at line 257 of file base_kinematics.h.
vector of every wheel attached to the base
Definition at line 272 of file base_kinematics.h.
| std::string controller::BaseKinematics::xml_caster_name_ | 
the name of the casters in the xml file
Definition at line 282 of file base_kinematics.h.
| std::string controller::BaseKinematics::xml_wheel_name_ | 
the name of the wheels in the xml file
Definition at line 287 of file base_kinematics.h.