Go to the documentation of this file.
38 #include <boost/shared_ptr.hpp>
41 #include <kdl/tree.hpp>
56 urdf::LinkConstSharedPtr link;
62 ROS_ERROR(
"Could not find link with name %s",link_name.c_str());
68 ROS_ERROR(
"Link %s does not have collision description. Add collision description for link to urdf.",link_name.c_str());
71 if(!link->collision->geometry)
73 ROS_ERROR(
"Link %s does not have collision geometry description. Add collision geometry description for link to urdf.",link_name.c_str());
76 if(link->collision->geometry->type != urdf::Geometry::CYLINDER)
78 ROS_ERROR(
"Link %s does not have cylinder geometry",link_name.c_str());
81 wheel_radius_ = (
dynamic_cast<urdf::Cylinder*
>(link->collision->geometry.get()))->radius;
92 urdf::Vector3
offset = link->parent_joint->parent_to_joint_origin_transform.position;
114 #if URDFDOM_1_0_0_API
115 urdf::LinkConstSharedPtr link;
121 ROS_ERROR(
"Could not find link with name %s",link_name.c_str());
124 ROS_DEBUG(
"caster name: %s",link_name.c_str());
133 urdf::Vector3
offset = link->parent_joint->parent_to_joint_origin_transform.position;
138 for(
unsigned int i=0;
i < link->child_links.size();
i++)
140 #if URDFDOM_1_0_0_API
141 urdf::LinkSharedPtr child = link->child_links[
i];
149 ROS_ERROR(
"Could not initialize caster %s",link_name.c_str());
160 std::string caster_names_string;
161 std::vector<std::string> caster_names;
170 node.
param<std::string> (
"caster_names",caster_names_string,
"");
171 std::stringstream ss(caster_names_string);
175 caster_names.push_back(tmp);
178 for(
unsigned int i=0;
i < caster_names.size();
i++)
183 ROS_DEBUG(
"caster name: %s",caster_names[
i].c_str());
187 ROS_ERROR(
"Could not initialize base kinematics");
195 node.
param<
double> (
"wheel_radius_multiplier", multiplier, 1.0);
196 int wheel_counter = 0;
199 for(
int i = 0;
i <
caster_[j].num_children_;
i++)
202 wheel_[wheel_counter].wheel_radius_*=multiplier;
231 geometry_msgs::Twist result;
232 result.linear.x = vel.linear.x - pos.y * vel.angular.z;
233 result.linear.y = vel.linear.y + pos.x * vel.angular.z;
234 result.angular.z = 0;
Caster * parent_
the caster on which this wheel is mounted
double steer_velocity_desired_
vector of desired caster steer speeds
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.
bool init(pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &node, std::string link_name)
double wheel_speed_cmd_
desired wheel speed
double caster_speed_
remembers the caster's current speed
pr2_mechanism_model::JointState * joint_
JointState for this caster joint.
int caster_stuck_
remembers if the caster is stalled
std::vector< Caster > caster_
vector of every caster attached to the base
double wheel_speed_filtered_
wheel speed filtered with alpha
std::vector< Wheel > wheel_
vector of every wheel attached to the base
double caster_speed_filtered_
caster speed filtered with alpha
BaseKinematics * parent_
BaseKinematics to which this caster belongs.
geometry_msgs::Point offset_
default offset from the parent caster before any transformations
std::string joint_name_
name of the joint
geometry_msgs::Point offset_
offset from the center of the base
int num_wheels_
number of wheels connected to the base
int direction_multiplier_
specifies the default direction of the wheel
std::string link_name_
name of the link
pr2_mechanism_model::JointState * joint_
JointState for this wheel joint.
JointState * getJointState(const std::string &name)
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...
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
double wheel_speed_actual_
actual wheel speeds
double wheel_radius_
wheel radius scale (based on the default wheel radius in Basekinematics)
pr2_mechanism_model::RobotState * robot_state_
remembers everything about the state of the robot
std::string joint_name_
name of the joint
double wheel_speed_error_
difference between desired and actual speed
void updatePosition()
Computes 2d postion of the wheel relative to the center of the base.
int num_children_
the number of child wheels that are attached to this caster
std::string name_
name of this BaseKinematics (generally associated with whatever controller is using it)
double steer_angle_actual_
actual caster steer angles
T param(const std::string ¶m_name, const T &default_val) const
std::string link_name_
name of the link
const std::string & getNamespace() const
double steer_angle_stored_
stored caster steer angles
bool init(pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &node)
Loads BaseKinematic's information from the xml description file and param server.
int num_casters_
number of casters connected to the base
void computeWheelPositions()
Computes 2d postion of every wheel relative to the center of the base.
double caster_speed_error_
difference between desired and actual speeds of the casters
int wheel_stuck_
remembers if the wheel is stalled