base_kinematics.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 /*
35  * Author: Sachin Chitta and Matthew Piccoli
36  */
37 
39 #include <kdl/tree.hpp>
40 
41 using namespace controller;
42 
43 
44 bool Wheel::init(pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &node, std::string link_name)
45 {
46  wheel_stuck_ = 0;
50  wheel_speed_cmd_ = 0;
52 
54  link = robot_state->model_->robot_model_.getLink(link_name);
55  if (!link){
56  ROS_ERROR("Could not find link with name %s",link_name.c_str());
57  return false;
58  }
59 
60  if(!link->collision)
61  {
62  ROS_ERROR("Link %s does not have collision description. Add collision description for link to urdf.",link_name.c_str());
63  return false;
64  }
65  if(!link->collision->geometry)
66  {
67  ROS_ERROR("Link %s does not have collision geometry description. Add collision geometry description for link to urdf.",link_name.c_str());
68  return false;
69  }
70  if(link->collision->geometry->type != urdf::Geometry::CYLINDER)
71  {
72  ROS_ERROR("Link %s does not have cylinder geometry",link_name.c_str());
73  return false;
74  }
75  wheel_radius_ = (dynamic_cast<urdf::Cylinder*>(link->collision->geometry.get()))->radius;
76  ROS_DEBUG("wheel name: %s, radius: %f",link_name.c_str(),wheel_radius_);
77  link_name_ = link_name;
78  joint_name_ = link->parent_joint->name;
79 
80  joint_ = robot_state->getJointState(joint_name_);
81  if (!joint_){
82  ROS_ERROR("Could not find joint with name %s",joint_name_.c_str());
83  return false;
84  }
85 
86  urdf::Vector3 offset = link->parent_joint->parent_to_joint_origin_transform.position;
87  offset_.x = offset.x;
88  offset_.y = offset.y;
89  offset_.z = offset.z;
90 // node.param<double> ("wheel_radius_scaler", wheel_radius_scaler_, 1.0);
91  ROS_DEBUG("Loading wheel: %s",link_name_.c_str());
92  ROS_DEBUG("offset_.x: %f, offset_.y: %f, offset_.z: %f", offset_.x, offset_.y, offset_.z);
93  return true;
94 }
95 
96 bool Caster::init(pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &node, std::string link_name)
97 {
98  caster_stuck_ = 0;
99  caster_speed_ = 0;
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;
106  num_children_ = 0;
107 
109  link = robot_state->model_->robot_model_.getLink(link_name);
110  if (!link){
111  ROS_ERROR("Could not find link with name %s",link_name.c_str());
112  return false;
113  }
114  ROS_DEBUG("caster name: %s",link_name.c_str());
115  link_name_ = link_name;
116  joint_name_ = link->parent_joint->name;
117 
118  joint_ = robot_state->getJointState(joint_name_);
119  if (!joint_){
120  ROS_ERROR("Could not find joint with name %s",joint_name_.c_str());
121  return false;
122  }
123  urdf::Vector3 offset = link->parent_joint->parent_to_joint_origin_transform.position;
124  offset_.x = offset.x;
125  offset_.y = offset.y;
126  offset_.z = offset.z;
127 
128  for(unsigned int i=0; i < link->child_links.size(); i++)
129  {
130  boost::shared_ptr<urdf::Link> child = link->child_links[i];
131  Wheel tmp;
132  parent_->wheel_.push_back(tmp);
133  if(!parent_->wheel_[parent_->num_wheels_].init(robot_state, node, child->name))
134  {
135  ROS_ERROR("Could not initialize caster %s",link_name.c_str());
136  return false;
137  }
138  parent_->num_wheels_++;
139  num_children_++;
140  }
141  return true;
142 }
143 
145 {
146  std::string caster_names_string;
147  std::vector<std::string> caster_names;
148  name_ = node.getNamespace();
149  //Initialize stuff
150  MAX_DT_ = 0.01;
151  num_wheels_ = 0;
152  num_casters_ = 0;
153 
154  robot_state_ = robot_state;
155 
156  node.param<std::string> ("caster_names",caster_names_string,"");
157  std::stringstream ss(caster_names_string);
158  std::string tmp;
159  while(ss >> tmp)
160  {
161  caster_names.push_back(tmp);
162  }
163 
164  for(unsigned int i=0; i < caster_names.size(); i++)
165  {
166  Caster tmp;
167  caster_.push_back(tmp);
168  caster_[num_casters_].parent_ = this;
169  ROS_DEBUG("caster name: %s",caster_names[i].c_str());
170  ros::NodeHandle n(name_);
171  if(!caster_[num_casters_].init(robot_state, n, caster_names[i]))
172  {
173  ROS_ERROR("Could not initialize base kinematics");
174  return false;
175  }
176  num_casters_++;
177  }
178 
179  // node.param<double> ("wheel_radius", wheel_radius_, 0.074792);
180  double multiplier;
181  node.param<double> ("wheel_radius_multiplier", multiplier, 1.0);
182  int wheel_counter = 0;
183  for(int j = 0; j < num_casters_; j++)
184  {
185  for(int i = 0; i < caster_[j].num_children_; i++)
186  {
187  wheel_[wheel_counter].parent_ = &(caster_[j]);
188  wheel_[wheel_counter].wheel_radius_*=multiplier;
189  wheel_counter++;
190  }
191  }
192  return true;
193 }
194 
196 {
197  geometry_msgs::Point result = parent_->offset_;
198  double costh = cos(parent_->joint_->position_);
199  double sinth = sin(parent_->joint_->position_);
200  result.x += costh * offset_.x - sinth * offset_.y;
201  result.y += sinth * offset_.x + costh * offset_.y;
202  result.z = 0.0;
203  position_ = result;
204 }
205 
207 {
208  for(int i = 0; i < num_wheels_; i++)
209  {
210  wheel_[i].updatePosition();
211  }
212 
213 }
214 
215 geometry_msgs::Twist BaseKinematics::pointVel2D(const geometry_msgs::Point& pos, const geometry_msgs::Twist& vel)
216 {
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;
221  return result;
222 }
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&#39;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&#39;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 &param_name, T &param_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&#39;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.
#define ROS_ERROR(...)
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.
#define ROS_DEBUG(...)


pr2_mechanism_controllers
Author(s): Sachin Chita, John Hsu, Melonee Wise
autogenerated on Mon Jun 10 2019 14:26:33