pr2_base_controller.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 #include <ros/node_handle.h>
40 #include <pr2_mechanism_controllers/BaseControllerState.h>
43 #include <geometry_msgs/Twist.h>
44 #include <angles/angles.h>
45 #include <boost/shared_ptr.hpp>
46 #include <boost/scoped_ptr.hpp>
48 
49 namespace controller
50 {
54  class Pr2BaseController: public pr2_controller_interface::Controller
55  {
56  public:
62 
68 
69  /*
70  * \brief The starting method is called by the realtime thread just before
71  * the first call to update. Overrides Controller.staring().
72  * @return Successful start
73  */
74  void starting();
75 
77 
78  /*
79  * \brief callback function for setting the desired velocity using a topic
80  * @param cmd_vel Velocity command of the base in m/s and rad/s
81  */
82  void setCommand(const geometry_msgs::Twist &cmd_vel);
83 
88  geometry_msgs::Twist getCommand();
89 
94  BaseKinematics base_kin_;
95 
99  pthread_mutex_t pr2_base_controller_lock_;
100 
105  void update();
106 
110  void setJointCommands();
111 
115  void setDesiredCasterSteer();
116 
117  private:
118 
120 
122 
124 
126 
130  double timeout_;
131 
135  bool new_cmd_available_;
136 
141 
146 
151  geometry_msgs::Twist cmd_vel_t_;
152 
156  geometry_msgs::Twist cmd_vel_;
157 
161  geometry_msgs::Twist desired_vel_;
162 
166  geometry_msgs::Twist max_vel_;
167 
171  geometry_msgs::Twist max_accel_;
172 
177 
182 
186  double kp_caster_steer_;
187 
191  double alpha_stall_;
192 
196  std::vector<boost::shared_ptr<JointVelocityController> > wheel_controller_;
197 
201  std::vector<boost::shared_ptr<JointVelocityController> > caster_controller_;
202 
206  boost::scoped_ptr<realtime_tools::RealtimePublisher<pr2_mechanism_controllers::BaseControllerState> > state_publisher_;
207 
211  void computeJointCommands(const double &dT);
212 
216  void updateJointControllers();
217 
221  void computeDesiredCasterSteer(const double &dT);
222 
227 
231  void setDesiredWheelSpeeds();
232 
236  geometry_msgs::Twist interpolateCommand(const geometry_msgs::Twist &start, const geometry_msgs::Twist &end, const geometry_msgs::Twist &max_rate, const double &dT);
237 
241  void commandCallback(const geometry_msgs::TwistConstPtr& msg);
242 
246  geometry_msgs::Twist base_vel_msg_;
247 
251  double eps_;
252 
256  double cmd_vel_rot_eps_;
257 
262 
267 
271  double cmd_vel_trans_eps_;
272 
273 
277  void publishState(const ros::Time &current_time);
278 
279  bool publish_state_;
280 
284  std::vector<control_toolbox::Pid> caster_position_pid_;
285 
287 
288  std::vector<double> filtered_velocity_;
289  };
290 
291 }
controller::Pr2BaseController::timeout_
double timeout_
timeout specifying time that the controller waits before setting the current velocity command to zero
Definition: pr2_base_controller.h:162
realtime_publisher.h
node_handle.h
controller::Pr2BaseController::publish_state_
bool publish_state_
Definition: pr2_base_controller.h:311
controller::Pr2BaseController::alpha_stall_
double alpha_stall_
low pass filter value used for finding stalls
Definition: pr2_base_controller.h:223
controller::Pr2BaseController::computeDesiredCasterSteer
void computeDesiredCasterSteer(const double &dT)
computes the desired caster speeds given the desired base speed
Definition: pr2_base_controller.cpp:405
controller::Pr2BaseController::Pr2BaseController
Pr2BaseController()
Default Constructor of the Pr2BaseController class.
Definition: pr2_base_controller.cpp:79
controller::Pr2BaseController::pr2_base_controller_lock_
pthread_mutex_t pr2_base_controller_lock_
mutex lock for setting and getting commands
Definition: pr2_base_controller.h:131
controller::Pr2BaseController::node_
ros::NodeHandle node_
Definition: pr2_base_controller.h:151
controller::Pr2BaseController::last_publish_time_
ros::Time last_publish_time_
Time interval between state publishing.
Definition: pr2_base_controller.h:298
controller::Pr2BaseController::cmd_sub_
ros::Subscriber cmd_sub_
Definition: pr2_base_controller.h:155
controller::Pr2BaseController::state_publisher_
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_mechanism_controllers::BaseControllerState > > state_publisher_
publishes information about the caster and wheel controllers
Definition: pr2_base_controller.h:238
controller::Pr2BaseController::cmd_vel_trans_eps_
double cmd_vel_trans_eps_
minimum tranlational velocity value allowable
Definition: pr2_base_controller.h:303
joint_velocity_controller.h
controller::Pr2BaseController::~Pr2BaseController
~Pr2BaseController()
Destructor of the Pr2BaseController class.
Definition: pr2_base_controller.cpp:100
controller::Pr2BaseController::max_vel_
geometry_msgs::Twist max_vel_
velocity limits specified externally
Definition: pr2_base_controller.h:198
controller::Pr2BaseController::setDesiredCasterSteer
void setDesiredCasterSteer()
set the desired caster steer
Definition: pr2_base_controller.cpp:453
controller::Pr2BaseController::max_rotational_velocity_
double max_rotational_velocity_
maximum rotational velocity magnitude allowable
Definition: pr2_base_controller.h:213
controller::Pr2BaseController::root_handle_
ros::NodeHandle root_handle_
Definition: pr2_base_controller.h:153
controller::Pr2BaseController::starting
void starting()
Definition: pr2_base_controller.cpp:296
controller::Pr2BaseController::new_cmd_available_
bool new_cmd_available_
true when new command received by node
Definition: pr2_base_controller.h:167
controller::Pr2BaseController::cmd_received_timestamp_
ros::Time cmd_received_timestamp_
timestamp corresponding to when the command received by the node
Definition: pr2_base_controller.h:177
controller::Pr2BaseController::max_accel_
geometry_msgs::Twist max_accel_
acceleration limits specified externally
Definition: pr2_base_controller.h:203
controller::Pr2BaseController::caster_position_pid_
std::vector< control_toolbox::Pid > caster_position_pid_
The pid controllers for caster position.
Definition: pr2_base_controller.h:316
filters::MultiChannelTransferFunctionFilter< double >
controller::Pr2BaseController::computeDesiredWheelSpeeds
void computeDesiredWheelSpeeds()
computes the desired wheel speeds given the desired base speed
Definition: pr2_base_controller.cpp:461
controller::Pr2BaseController::getCommand
geometry_msgs::Twist getCommand()
Returns the current position command.
Definition: pr2_base_controller.cpp:285
transfer_function.hpp
controller::Pr2BaseController::base_vel_msg_
geometry_msgs::Twist base_vel_msg_
callback message, used to remember where the base is commanded to go
Definition: pr2_base_controller.h:278
controller::Pr2BaseController::setJointCommands
void setJointCommands()
set the joint commands
Definition: pr2_base_controller.cpp:398
controller::Pr2BaseController::state_publish_time_
double state_publish_time_
Time interval between state publishing.
Definition: pr2_base_controller.h:293
controller
pr2_mechanism_model::RobotState
controller::Pr2BaseController::computeJointCommands
void computeJointCommands(const double &dT)
computes the desired caster steers and wheel speeds
Definition: pr2_base_controller.cpp:389
controller::Pr2BaseController::filtered_velocity_
std::vector< double > filtered_velocity_
Definition: pr2_base_controller.h:320
controller::Pr2BaseController::cmd_vel_t_
geometry_msgs::Twist cmd_vel_t_
Input speed command vector represents the desired speed requested by the node. Note that this may dif...
Definition: pr2_base_controller.h:183
controller::Pr2BaseController::wheel_controller_
std::vector< boost::shared_ptr< JointVelocityController > > wheel_controller_
vector that stores the wheel controllers
Definition: pr2_base_controller.h:228
controller::Pr2BaseController::commandCallback
void commandCallback(const geometry_msgs::TwistConstPtr &msg)
deal with Twist commands
Definition: pr2_base_controller.cpp:506
controller::Pr2BaseController::setDesiredWheelSpeeds
void setDesiredWheelSpeeds()
sends the desired wheel speeds to the wheel controllers
Definition: pr2_base_controller.cpp:490
controller::Pr2BaseController::base_kin_
BaseKinematics base_kin_
class where the robot's information is computed and stored
Definition: pr2_base_controller.h:126
controller::Pr2BaseController::cmd_vel_rot_eps_
double cmd_vel_rot_eps_
minimum rotational velocity value allowable
Definition: pr2_base_controller.h:288
pr2_controller_interface::Controller
controller::Pr2BaseController::eps_
double eps_
generic epsilon value that is used as a minimum or maximum allowable input value
Definition: pr2_base_controller.h:283
controller::Pr2BaseController::updateJointControllers
void updateJointControllers()
tells the wheel and caster controllers to update their speeds
Definition: pr2_base_controller.cpp:498
ros::Time
controller::Pr2BaseController::max_translational_velocity_
double max_translational_velocity_
maximum translational velocity magnitude allowable
Definition: pr2_base_controller.h:208
controller::Pr2BaseController::publishState
void publishState(const ros::Time &current_time)
Publish the state.
Definition: pr2_base_controller.cpp:349
controller::Pr2BaseController::setCommand
void setCommand(const geometry_msgs::Twist &cmd_vel)
Definition: pr2_base_controller.cpp:213
controller::Pr2BaseController::init
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
Definition: pr2_base_controller.cpp:106
controller::Pr2BaseController::kp_caster_steer_
double kp_caster_steer_
local gain used for speed control of the caster (to achieve resultant position control)
Definition: pr2_base_controller.h:218
controller::Pr2BaseController::state_publish_rate_
double state_publish_rate_
Definition: pr2_base_controller.h:293
controller::Pr2BaseController::interpolateCommand
geometry_msgs::Twist interpolateCommand(const geometry_msgs::Twist &start, const geometry_msgs::Twist &end, const geometry_msgs::Twist &max_rate, const double &dT)
interpolates velocities within a given time based on maximum accelerations
Definition: pr2_base_controller.cpp:246
controller::Pr2BaseController::desired_vel_
geometry_msgs::Twist desired_vel_
Input speed command vector represents the desired speed requested by the node.
Definition: pr2_base_controller.h:193
controller::Pr2BaseController::cmd_vel_
geometry_msgs::Twist cmd_vel_
speed command vector used internally to represent the current commanded speed
Definition: pr2_base_controller.h:188
base_kinematics.h
controller::Pr2BaseController::update
void update()
(a) Updates commands to caster and wheels. Called every timestep in realtime
Definition: pr2_base_controller.cpp:310
controller::Pr2BaseController::caster_vel_filter_
filters::MultiChannelTransferFunctionFilter< double > caster_vel_filter_
Definition: pr2_base_controller.h:318
controller::Pr2BaseController::cmd_sub_deprecated_
ros::Subscriber cmd_sub_deprecated_
Definition: pr2_base_controller.h:157
ros::NodeHandle
ros::Subscriber
angles.h
controller::Pr2BaseController::last_time_
ros::Time last_time_
time corresponding to when update was last called
Definition: pr2_base_controller.h:172
controller::Pr2BaseController::caster_controller_
std::vector< boost::shared_ptr< JointVelocityController > > caster_controller_
vector that stores the caster controllers
Definition: pr2_base_controller.h:233


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