base_kinematics.h
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 
38 #ifndef PR2_BASE_KINEMATICS_H
39 #define PR2_BASE_KINEMATICS_H
40 
43 #include <geometry_msgs/Twist.h>
44 #include <geometry_msgs/Point.h>
46 #include <boost/thread/condition.hpp>
47 
48 namespace controller
49 {
50  class Wheel;
51  class Caster;
52  class BaseKinematics;
56  class Wheel
57  {
58  public:
59 
64 
68  geometry_msgs::Point offset_;
69 
73  std::string joint_name_;
74 
78  std::string link_name_;
79 
80 
84  geometry_msgs::Point position_;
85 
89  Caster *parent_;
90 
94  double wheel_speed_actual_;
95 
99  double wheel_speed_cmd_;
100 
104  double wheel_speed_error_;
105 
109  double wheel_speed_filtered_;
110 
115 
119  int wheel_stuck_;
120 
124  double wheel_radius_;
125 
131  bool init(pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &node, std::string link_name);
132 
137  };
138 
142  class Caster
143  {
144  public:
145 
150 
154  geometry_msgs::Point offset_;
155 
159  std::string link_name_;
160 
164  std::string joint_name_;
165 
166  //geometry_msgs::Point position_;
167 
172 
176  int num_children_;
177 
182 
187 
192 
197 
201  double caster_position_error_;
202 
206  double caster_speed_error_;
207 
211  double caster_speed_filtered_;
212 
216  double caster_speed_;
217 
221  int caster_stuck_;
222 
223  bool init(pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &node, std::string link_name);
224  };
225 
229  class BaseKinematics
230  {
231  public:
232 
239  bool init(pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &node);
240 
244  void computeWheelPositions();
245 
252  geometry_msgs::Twist pointVel2D(const geometry_msgs::Point& pos, const geometry_msgs::Twist& vel);
253 
258 
262  int num_wheels_;
263 
267  int num_casters_;
268 
272  std::vector<Wheel> wheel_;
273 
277  std::vector<Caster> caster_;
278 
282  std::string xml_caster_name_;
283 
287  std::string xml_wheel_name_;
288 
292  std::string name_;
293 
297  double MAX_DT_;
298 
302  std::string robot_base_id_;
303  };
304 } // namespace
305 #endif
controller::Wheel::parent_
Caster * parent_
the caster on which this wheel is mounted
Definition: base_kinematics.h:121
pr2_mechanism_model::JointState
controller::Caster::steer_velocity_desired_
double steer_velocity_desired_
vector of desired caster steer speeds
Definition: base_kinematics.h:223
controller::Wheel::init
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.
Definition: base_kinematics.cpp:46
controller::Caster::init
bool init(pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &node, std::string link_name)
Definition: base_kinematics.cpp:102
controller::Wheel::wheel_speed_cmd_
double wheel_speed_cmd_
desired wheel speed
Definition: base_kinematics.h:131
controller::Caster::caster_speed_
double caster_speed_
remembers the caster's current speed
Definition: base_kinematics.h:248
filters.h
controller::Caster::joint_
pr2_mechanism_model::JointState * joint_
JointState for this caster joint.
Definition: base_kinematics.h:181
controller::Caster::caster_stuck_
int caster_stuck_
remembers if the caster is stalled
Definition: base_kinematics.h:253
controller::BaseKinematics::caster_
std::vector< Caster > caster_
vector of every caster attached to the base
Definition: base_kinematics.h:309
controller::Wheel::wheel_speed_filtered_
double wheel_speed_filtered_
wheel speed filtered with alpha
Definition: base_kinematics.h:141
controller::BaseKinematics::wheel_
std::vector< Wheel > wheel_
vector of every wheel attached to the base
Definition: base_kinematics.h:304
controller::Caster::caster_speed_filtered_
double caster_speed_filtered_
caster speed filtered with alpha
Definition: base_kinematics.h:243
controller::BaseKinematics::xml_caster_name_
std::string xml_caster_name_
the name of the casters in the xml file
Definition: base_kinematics.h:314
controller::Caster::parent_
BaseKinematics * parent_
BaseKinematics to which this caster belongs.
Definition: base_kinematics.h:203
controller::BaseKinematics
Definition: base_kinematics.h:261
controller::Wheel::offset_
geometry_msgs::Point offset_
default offset from the parent caster before any transformations
Definition: base_kinematics.h:100
controller::Caster::joint_name_
std::string joint_name_
name of the joint
Definition: base_kinematics.h:196
controller::Caster::offset_
geometry_msgs::Point offset_
offset from the center of the base
Definition: base_kinematics.h:186
controller::BaseKinematics::num_wheels_
int num_wheels_
number of wheels connected to the base
Definition: base_kinematics.h:294
controller::Wheel::direction_multiplier_
int direction_multiplier_
specifies the default direction of the wheel
Definition: base_kinematics.h:146
controller.h
controller
pr2_mechanism_model::RobotState
controller::Wheel::link_name_
std::string link_name_
name of the link
Definition: base_kinematics.h:110
controller::Wheel::joint_
pr2_mechanism_model::JointState * joint_
JointState for this wheel joint.
Definition: base_kinematics.h:95
controller::BaseKinematics::pointVel2D
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...
Definition: base_kinematics.cpp:229
controller::Caster::caster_position_error_
double caster_position_error_
difference between desired and actual angles of the casters
Definition: base_kinematics.h:233
controller::BaseKinematics::MAX_DT_
double MAX_DT_
maximum dT used in computation of interpolated velocity command
Definition: base_kinematics.h:329
controller::Wheel::position_
geometry_msgs::Point position_
offset_ after rotation transformation from the parent caster's position
Definition: base_kinematics.h:116
controller::Wheel::wheel_speed_actual_
double wheel_speed_actual_
actual wheel speeds
Definition: base_kinematics.h:126
controller::Wheel::wheel_radius_
double wheel_radius_
wheel radius scale (based on the default wheel radius in Basekinematics)
Definition: base_kinematics.h:156
controller::BaseKinematics::robot_state_
pr2_mechanism_model::RobotState * robot_state_
remembers everything about the state of the robot
Definition: base_kinematics.h:289
controller::Wheel::joint_name_
std::string joint_name_
name of the joint
Definition: base_kinematics.h:105
controller::BaseKinematics::xml_wheel_name_
std::string xml_wheel_name_
the name of the wheels in the xml file
Definition: base_kinematics.h:319
controller::Wheel::wheel_speed_error_
double wheel_speed_error_
difference between desired and actual speed
Definition: base_kinematics.h:136
controller::Caster::steer_angle_desired_
double steer_angle_desired_
actual caster steer angles
Definition: base_kinematics.h:218
controller::Caster
Definition: base_kinematics.h:174
controller::Wheel::updatePosition
void updatePosition()
Computes 2d postion of the wheel relative to the center of the base.
Definition: base_kinematics.cpp:209
controller::Caster::num_children_
int num_children_
the number of child wheels that are attached to this caster
Definition: base_kinematics.h:208
controller::BaseKinematics::name_
std::string name_
name of this BaseKinematics (generally associated with whatever controller is using it)
Definition: base_kinematics.h:324
controller::Caster::steer_angle_actual_
double steer_angle_actual_
actual caster steer angles
Definition: base_kinematics.h:213
controller::BaseKinematics::robot_base_id_
std::string robot_base_id_
Name(string id) of the robot base frame.
Definition: base_kinematics.h:334
controller::Caster::link_name_
std::string link_name_
name of the link
Definition: base_kinematics.h:191
controller::Caster::steer_angle_stored_
double steer_angle_stored_
stored caster steer angles
Definition: base_kinematics.h:228
controller::BaseKinematics::init
bool init(pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &node)
Loads BaseKinematic's information from the xml description file and param server.
Definition: base_kinematics.cpp:158
controller::BaseKinematics::num_casters_
int num_casters_
number of casters connected to the base
Definition: base_kinematics.h:299
controller::BaseKinematics::computeWheelPositions
void computeWheelPositions()
Computes 2d postion of every wheel relative to the center of the base.
Definition: base_kinematics.cpp:220
controller::Caster::caster_speed_error_
double caster_speed_error_
difference between desired and actual speeds of the casters
Definition: base_kinematics.h:238
controller::Wheel::wheel_stuck_
int wheel_stuck_
remembers if the wheel is stalled
Definition: base_kinematics.h:151
ros::NodeHandle
robot.h


pr2_mechanism_controllers
Author(s): Sachin Chita, John Hsu, Melonee Wise
autogenerated on Sat Nov 12 2022 03:33:25