39 #include <kdl/tree.hpp> 56 ROS_ERROR(
"Could not find link with name %s",link_name.c_str());
62 ROS_ERROR(
"Link %s does not have collision description. Add collision description for link to urdf.",link_name.c_str());
65 if(!link->collision->geometry)
67 ROS_ERROR(
"Link %s does not have collision geometry description. Add collision geometry description for link to urdf.",link_name.c_str());
70 if(link->collision->geometry->type != urdf::Geometry::CYLINDER)
72 ROS_ERROR(
"Link %s does not have cylinder geometry",link_name.c_str());
75 wheel_radius_ = (
dynamic_cast<urdf::Cylinder*
>(link->collision->geometry.get()))->radius;
86 urdf::Vector3
offset = link->parent_joint->parent_to_joint_origin_transform.position;
91 ROS_DEBUG(
"Loading wheel: %s",link_name_.c_str());
100 caster_speed_filtered_ = 0;
101 caster_speed_error_ = 0;
102 caster_position_error_ = 0;
103 steer_angle_stored_ = 0;
104 steer_velocity_desired_ = 0;
105 steer_angle_actual_ = 0;
111 ROS_ERROR(
"Could not find link with name %s",link_name.c_str());
114 ROS_DEBUG(
"caster name: %s",link_name.c_str());
123 urdf::Vector3
offset = link->parent_joint->parent_to_joint_origin_transform.position;
128 for(
unsigned int i=0; i < link->child_links.size(); i++)
132 parent_->wheel_.push_back(tmp);
135 ROS_ERROR(
"Could not initialize caster %s",link_name.c_str());
146 std::string caster_names_string;
147 std::vector<std::string> caster_names;
154 robot_state_ = robot_state;
156 node.
param<std::string> (
"caster_names",caster_names_string,
"");
157 std::stringstream ss(caster_names_string);
161 caster_names.push_back(tmp);
164 for(
unsigned int i=0; i < caster_names.size(); i++)
167 caster_.push_back(tmp);
168 caster_[num_casters_].
parent_ =
this;
169 ROS_DEBUG(
"caster name: %s",caster_names[i].c_str());
171 if(!caster_[num_casters_].
init(robot_state, n, caster_names[i]))
173 ROS_ERROR(
"Could not initialize base kinematics");
181 node.
param<
double> (
"wheel_radius_multiplier", multiplier, 1.0);
182 int wheel_counter = 0;
183 for(
int j = 0; j < num_casters_; j++)
185 for(
int i = 0; i < caster_[j].num_children_; i++)
187 wheel_[wheel_counter].parent_ = &(caster_[j]);
188 wheel_[wheel_counter].wheel_radius_*=multiplier;
208 for(
int i = 0; i < num_wheels_; i++)
210 wheel_[i].updatePosition();
217 geometry_msgs::Twist result;
218 result.linear.x = vel.linear.x - pos.y * vel.angular.z;
219 result.linear.y = vel.linear.y + pos.x * vel.angular.z;
220 result.angular.z = 0;
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)
geometry_msgs::Point offset_
offset from the center of the base
bool init(pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &node, std::string link_name)
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
geometry_msgs::Point offset_
default offset from the parent caster before any transformations
geometry_msgs::Point position_
offset_ after rotation transformation from the parent caster's position
int wheel_stuck_
remembers if the wheel is stalled
Caster * parent_
the caster on which this wheel is mounted
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 wheel_speed_actual_
actual wheel speeds
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
const std::string & getNamespace() const
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.
JointState * getJointState(const std::string &name)
double wheel_speed_filtered_
wheel speed filtered with alpha
bool init(pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &node)
Loads BaseKinematic's information from the xml description file and param server. ...
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
void computeWheelPositions()
Computes 2d postion of every wheel relative to the center of the base.
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
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.