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 
53 #if URDFDOM_1_0_0_API
54  urdf::LinkConstSharedPtr link;
55 #else
57 #endif
58  link = robot_state->model_->robot_model_.getLink(link_name);
59  if (!link){
60  ROS_ERROR("Could not find link with name %s",link_name.c_str());
61  return false;
62  }
63 
64  if(!link->collision)
65  {
66  ROS_ERROR("Link %s does not have collision description. Add collision description for link to urdf.",link_name.c_str());
67  return false;
68  }
69  if(!link->collision->geometry)
70  {
71  ROS_ERROR("Link %s does not have collision geometry description. Add collision geometry description for link to urdf.",link_name.c_str());
72  return false;
73  }
74  if(link->collision->geometry->type != urdf::Geometry::CYLINDER)
75  {
76  ROS_ERROR("Link %s does not have cylinder geometry",link_name.c_str());
77  return false;
78  }
79  wheel_radius_ = (dynamic_cast<urdf::Cylinder*>(link->collision->geometry.get()))->radius;
80  ROS_DEBUG("wheel name: %s, radius: %f",link_name.c_str(),wheel_radius_);
81  link_name_ = link_name;
82  joint_name_ = link->parent_joint->name;
83 
84  joint_ = robot_state->getJointState(joint_name_);
85  if (!joint_){
86  ROS_ERROR("Could not find joint with name %s",joint_name_.c_str());
87  return false;
88  }
89 
90  urdf::Vector3 offset = link->parent_joint->parent_to_joint_origin_transform.position;
91  offset_.x = offset.x;
92  offset_.y = offset.y;
93  offset_.z = offset.z;
94 // node.param<double> ("wheel_radius_scaler", wheel_radius_scaler_, 1.0);
95  ROS_DEBUG("Loading wheel: %s",link_name_.c_str());
96  ROS_DEBUG("offset_.x: %f, offset_.y: %f, offset_.z: %f", offset_.x, offset_.y, offset_.z);
97  return true;
98 }
99 
100 bool Caster::init(pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &node, std::string link_name)
101 {
102  caster_stuck_ = 0;
103  caster_speed_ = 0;
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;
110  num_children_ = 0;
111 
112 #if URDFDOM_1_0_0_API
113  urdf::LinkConstSharedPtr link;
114 #else
116 #endif
117  link = robot_state->model_->robot_model_.getLink(link_name);
118  if (!link){
119  ROS_ERROR("Could not find link with name %s",link_name.c_str());
120  return false;
121  }
122  ROS_DEBUG("caster name: %s",link_name.c_str());
123  link_name_ = link_name;
124  joint_name_ = link->parent_joint->name;
125 
126  joint_ = robot_state->getJointState(joint_name_);
127  if (!joint_){
128  ROS_ERROR("Could not find joint with name %s",joint_name_.c_str());
129  return false;
130  }
131  urdf::Vector3 offset = link->parent_joint->parent_to_joint_origin_transform.position;
132  offset_.x = offset.x;
133  offset_.y = offset.y;
134  offset_.z = offset.z;
135 
136  for(unsigned int i=0; i < link->child_links.size(); i++)
137  {
138 #if URDFDOM_1_0_0_API
139  urdf::LinkSharedPtr child = link->child_links[i];
140 #else
141  boost::shared_ptr<urdf::Link> child = link->child_links[i];
142 #endif
143  Wheel tmp;
144  parent_->wheel_.push_back(tmp);
145  if(!parent_->wheel_[parent_->num_wheels_].init(robot_state, node, child->name))
146  {
147  ROS_ERROR("Could not initialize caster %s",link_name.c_str());
148  return false;
149  }
150  parent_->num_wheels_++;
151  num_children_++;
152  }
153  return true;
154 }
155 
157 {
158  std::string caster_names_string;
159  std::vector<std::string> caster_names;
160  name_ = node.getNamespace();
161  //Initialize stuff
162  MAX_DT_ = 0.01;
163  num_wheels_ = 0;
164  num_casters_ = 0;
165 
166  robot_state_ = robot_state;
167 
168  node.param<std::string> ("caster_names",caster_names_string,"");
169  std::stringstream ss(caster_names_string);
170  std::string tmp;
171  while(ss >> tmp)
172  {
173  caster_names.push_back(tmp);
174  }
175 
176  for(unsigned int i=0; i < caster_names.size(); i++)
177  {
178  Caster tmp;
179  caster_.push_back(tmp);
180  caster_[num_casters_].parent_ = this;
181  ROS_DEBUG("caster name: %s",caster_names[i].c_str());
182  ros::NodeHandle n(name_);
183  if(!caster_[num_casters_].init(robot_state, n, caster_names[i]))
184  {
185  ROS_ERROR("Could not initialize base kinematics");
186  return false;
187  }
188  num_casters_++;
189  }
190 
191  // node.param<double> ("wheel_radius", wheel_radius_, 0.074792);
192  double multiplier;
193  node.param<double> ("wheel_radius_multiplier", multiplier, 1.0);
194  int wheel_counter = 0;
195  for(int j = 0; j < num_casters_; j++)
196  {
197  for(int i = 0; i < caster_[j].num_children_; i++)
198  {
199  wheel_[wheel_counter].parent_ = &(caster_[j]);
200  wheel_[wheel_counter].wheel_radius_*=multiplier;
201  wheel_counter++;
202  }
203  }
204  return true;
205 }
206 
208 {
209  geometry_msgs::Point result = parent_->offset_;
210  double costh = cos(parent_->joint_->position_);
211  double sinth = sin(parent_->joint_->position_);
212  result.x += costh * offset_.x - sinth * offset_.y;
213  result.y += sinth * offset_.x + costh * offset_.y;
214  result.z = 0.0;
215  position_ = result;
216 }
217 
219 {
220  for(int i = 0; i < num_wheels_; i++)
221  {
222  wheel_[i].updatePosition();
223  }
224 
225 }
226 
227 geometry_msgs::Twist BaseKinematics::pointVel2D(const geometry_msgs::Point& pos, const geometry_msgs::Twist& vel)
228 {
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;
233  return result;
234 }
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 Wed Jun 5 2019 19:34:08