39 #include <kdl/tree.hpp> 54 urdf::LinkConstSharedPtr link;
60 ROS_ERROR(
"Could not find link with name %s",link_name.c_str());
66 ROS_ERROR(
"Link %s does not have collision description. Add collision description for link to urdf.",link_name.c_str());
69 if(!link->collision->geometry)
71 ROS_ERROR(
"Link %s does not have collision geometry description. Add collision geometry description for link to urdf.",link_name.c_str());
74 if(link->collision->geometry->type != urdf::Geometry::CYLINDER)
76 ROS_ERROR(
"Link %s does not have cylinder geometry",link_name.c_str());
79 wheel_radius_ = (
dynamic_cast<urdf::Cylinder*
>(link->collision->geometry.get()))->radius;
90 urdf::Vector3
offset = link->parent_joint->parent_to_joint_origin_transform.position;
95 ROS_DEBUG(
"Loading wheel: %s",link_name_.c_str());
104 caster_speed_filtered_ = 0;
105 caster_speed_error_ = 0;
106 caster_position_error_ = 0;
107 steer_angle_stored_ = 0;
108 steer_velocity_desired_ = 0;
109 steer_angle_actual_ = 0;
112 #if URDFDOM_1_0_0_API 113 urdf::LinkConstSharedPtr link;
119 ROS_ERROR(
"Could not find link with name %s",link_name.c_str());
122 ROS_DEBUG(
"caster name: %s",link_name.c_str());
131 urdf::Vector3
offset = link->parent_joint->parent_to_joint_origin_transform.position;
136 for(
unsigned int i=0; i < link->child_links.size(); i++)
138 #if URDFDOM_1_0_0_API 139 urdf::LinkSharedPtr child = link->child_links[i];
144 parent_->wheel_.push_back(tmp);
147 ROS_ERROR(
"Could not initialize caster %s",link_name.c_str());
158 std::string caster_names_string;
159 std::vector<std::string> caster_names;
166 robot_state_ = robot_state;
168 node.
param<std::string> (
"caster_names",caster_names_string,
"");
169 std::stringstream ss(caster_names_string);
173 caster_names.push_back(tmp);
176 for(
unsigned int i=0; i < caster_names.size(); i++)
179 caster_.push_back(tmp);
180 caster_[num_casters_].
parent_ =
this;
181 ROS_DEBUG(
"caster name: %s",caster_names[i].c_str());
183 if(!caster_[num_casters_].
init(robot_state, n, caster_names[i]))
185 ROS_ERROR(
"Could not initialize base kinematics");
193 node.
param<
double> (
"wheel_radius_multiplier", multiplier, 1.0);
194 int wheel_counter = 0;
195 for(
int j = 0; j < num_casters_; j++)
197 for(
int i = 0; i < caster_[j].num_children_; i++)
199 wheel_[wheel_counter].parent_ = &(caster_[j]);
200 wheel_[wheel_counter].wheel_radius_*=multiplier;
220 for(
int i = 0; i < num_wheels_; i++)
222 wheel_[i].updatePosition();
229 geometry_msgs::Twist result;
230 result.linear.x = vel.linear.x - pos.y * vel.angular.z;
231 result.linear.y = vel.linear.y + pos.x * vel.angular.z;
232 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.