#include <base_kinematics.h>
Public Member Functions | |
bool | init (pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &node, std::string link_name) |
Public Attributes | |
double | caster_position_error_ |
difference between desired and actual angles of the casters | |
double | caster_speed_ |
remembers the caster's current speed | |
double | caster_speed_error_ |
difference between desired and actual speeds of the casters | |
double | caster_speed_filtered_ |
caster speed filtered with alpha | |
int | caster_stuck_ |
remembers if the caster is stalled | |
pr2_mechanism_model::JointState * | joint_ |
JointState for this caster joint. | |
std::string | joint_name_ |
name of the joint | |
std::string | link_name_ |
name of the link | |
int | num_children_ |
the number of child wheels that are attached to this caster | |
geometry_msgs::Point | offset_ |
offset from the center of the base | |
BaseKinematics * | parent_ |
BaseKinematics to which this caster belongs. | |
double | steer_angle_actual_ |
actual caster steer angles | |
double | steer_angle_desired_ |
actual caster steer angles | |
double | steer_angle_stored_ |
stored caster steer angles | |
double | steer_velocity_desired_ |
vector of desired caster steer speeds |
Definition at line 139 of file base_kinematics.h.
bool Caster::init | ( | pr2_mechanism_model::RobotState * | robot_state, | |
ros::NodeHandle & | node, | |||
std::string | link_name | |||
) |
Definition at line 96 of file base_kinematics.cpp.
difference between desired and actual angles of the casters
Definition at line 198 of file base_kinematics.h.
remembers the caster's current speed
Definition at line 213 of file base_kinematics.h.
difference between desired and actual speeds of the casters
Definition at line 203 of file base_kinematics.h.
caster speed filtered with alpha
Definition at line 208 of file base_kinematics.h.
remembers if the caster is stalled
Definition at line 218 of file base_kinematics.h.
pr2_mechanism_model::JointState* controller::Caster::joint_ |
JointState for this caster joint.
Definition at line 146 of file base_kinematics.h.
std::string controller::Caster::joint_name_ |
name of the joint
Definition at line 161 of file base_kinematics.h.
std::string controller::Caster::link_name_ |
name of the link
Definition at line 156 of file base_kinematics.h.
the number of child wheels that are attached to this caster
Definition at line 173 of file base_kinematics.h.
geometry_msgs::Point controller::Caster::offset_ |
offset from the center of the base
Definition at line 151 of file base_kinematics.h.
BaseKinematics to which this caster belongs.
Definition at line 168 of file base_kinematics.h.
actual caster steer angles
Definition at line 178 of file base_kinematics.h.
actual caster steer angles
Definition at line 183 of file base_kinematics.h.
stored caster steer angles
Definition at line 193 of file base_kinematics.h.
vector of desired caster steer speeds
Definition at line 188 of file base_kinematics.h.