38 #ifndef PR2_BASE_KINEMATICS_H 39 #define PR2_BASE_KINEMATICS_H 43 #include <geometry_msgs/Twist.h> 44 #include <geometry_msgs/Point.h> 46 #include <boost/thread/condition.hpp> 244 void computeWheelPositions();
252 geometry_msgs::Twist pointVel2D(
const geometry_msgs::Point& pos,
const geometry_msgs::Twist& vel);
double wheel_speed_cmd_
desired wheel speed
pr2_mechanism_model::JointState * joint_
JointState for this caster joint.
std::string link_name_
name of the link
double wheel_radius_
wheel radius scale (based on the default wheel radius in Basekinematics)
double caster_speed_
remembers the caster's current speed
std::string joint_name_
name of the joint
geometry_msgs::Point offset_
offset from the center of the base
std::string xml_caster_name_
the name of the casters in the xml file
double caster_speed_filtered_
caster speed filtered with alpha
std::vector< Caster > caster_
vector of every caster attached to the base
int caster_stuck_
remembers if the caster is stalled
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.
std::string joint_name_
name of the joint
double steer_velocity_desired_
vector of desired caster steer speeds
geometry_msgs::Point offset_
default offset from the parent caster before any transformations
double caster_position_error_
difference between desired and actual angles of the casters
double MAX_DT_
maximum dT used in computation of interpolated velocity command
geometry_msgs::Point position_
offset_ after rotation transformation from the parent caster's position
int wheel_stuck_
remembers if the wheel is stalled
int num_wheels_
number of wheels connected to the base
std::vector< Wheel > wheel_
vector of every wheel attached to the base
Caster * parent_
the caster on which this wheel is mounted
double wheel_speed_actual_
actual wheel speeds
int direction_multiplier_
specifies the default direction of the wheel
BaseKinematics * parent_
BaseKinematics to which this caster belongs.
pr2_mechanism_model::JointState * joint_
JointState for this wheel joint.
int num_children_
the number of child wheels that are attached to this caster
std::string xml_wheel_name_
the name of the wheels in the xml file
double steer_angle_actual_
actual caster steer angles
double caster_speed_error_
difference between desired and actual speeds of the casters
double wheel_speed_filtered_
wheel speed filtered with alpha
std::string name_
name of this BaseKinematics (generally associated with whatever controller is using it) ...
double steer_angle_desired_
actual caster steer angles
std::string robot_base_id_
Name(string id) of the robot base frame.
double steer_angle_stored_
stored caster steer angles
pr2_mechanism_model::RobotState * robot_state_
remembers everything about the state of the robot
int num_casters_
number of casters connected to the base
double wheel_speed_error_
difference between desired and actual speed
std::string link_name_
name of the link
void updatePosition()
Computes 2d postion of the wheel relative to the center of the base.