pr2_base_controller2.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/BaseControllerState2.h>
43 #include <geometry_msgs/Twist.h>
44 #include <angles/angles.h>
45 #include <boost/shared_ptr.hpp>
46 #include <boost/scoped_ptr.hpp>
47 #include <filters/transfer_function.hpp>
48 
49 namespace controller
50 {
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 
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 
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 
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::BaseControllerState2> > state_publisher_;
207 
211  void computeJointCommands(const double &dT);
212 
216  void updateJointControllers();
217 
221  void computeDesiredCasterSteer(const double &dT);
222 
226  void computeDesiredWheelSpeeds(const double &dT);
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 
257 
262 
267 
272 
273 
277  void publishState(const ros::Time &current_time);
278 
280 
284  std::vector<control_toolbox::Pid> caster_position_pid_;
285 
287 
288  std::vector<double> filtered_velocity_;
289 
291 
292  std::vector<double> filtered_wheel_velocity_;
293 
297  std::vector<control_toolbox::Pid> wheel_pid_controllers_;
298  };
299 
300 }
double max_rotational_velocity_
maximum rotational velocity magnitude allowable
std::vector< control_toolbox::Pid > wheel_pid_controllers_
The pid controllers for caster position.
void computeJointCommands(const double &dT)
computes the desired caster steers and wheel speeds
void setDesiredCasterSteer()
set the desired caster steer
double max_translational_velocity_
maximum translational velocity magnitude allowable
geometry_msgs::Twist base_vel_msg_
callback message, used to remember where the base is commanded to go
geometry_msgs::Twist cmd_vel_t_
Input speed command vector represents the desired speed requested by the node. Note that this may dif...
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
pthread_mutex_t pr2_base_controller_lock_
mutex lock for setting and getting commands
BaseKinematics base_kinematics_
class where the robot&#39;s information is computed and stored
void setCommand(const geometry_msgs::Twist &cmd_vel)
double cmd_vel_trans_eps_
minimum tranlational velocity value allowable
void computeDesiredWheelSpeeds(const double &dT)
computes the desired wheel speeds given the desired base speed
~Pr2BaseController2()
Destructor of the Pr2BaseController2 class.
double kp_caster_steer_
local gain used for speed control of the caster (to achieve resultant position control) ...
void commandCallback(const geometry_msgs::TwistConstPtr &msg)
deal with Twist commands
std::vector< double > filtered_velocity_
double timeout_
timeout specifying time that the controller waits before setting the current velocity command to zero...
void update()
(a) Updates commands to caster and wheels. Called every timestep in realtime
geometry_msgs::Twist max_accel_
acceleration limits specified externally
filters::MultiChannelTransferFunctionFilter< double > caster_vel_filter_
std::vector< double > filtered_wheel_velocity_
void setJointCommands()
set the joint commands
geometry_msgs::Twist getCommand()
Returns the current position command.
void updateJointControllers()
tells the wheel and caster controllers to update their speeds
geometry_msgs::Twist desired_vel_
Input speed command vector represents the desired speed requested by the node.
std::vector< control_toolbox::Pid > caster_position_pid_
The pid controllers for caster position.
geometry_msgs::Twist max_vel_
velocity limits specified externally
std::vector< boost::shared_ptr< JointVelocityController > > wheel_controller_
vector that stores the wheel controllers
std::vector< boost::shared_ptr< JointVelocityController > > caster_controller_
vector that stores the caster controllers
double alpha_stall_
low pass filter value used for finding stalls
filters::MultiChannelTransferFunctionFilter< double > wheel_vel_filter_
Pr2BaseController2()
Default Constructor of the Pr2BaseController2 class.
ros::Time last_time_
time corresponding to when update was last called
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
void computeDesiredCasterSteer(const double &dT)
computes the desired caster speeds given the desired base speed
double eps_
generic epsilon value that is used as a minimum or maximum allowable input value
double cmd_vel_rot_eps_
minimum rotational velocity value allowable
ros::Time last_publish_time_
Time interval between state publishing.
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_mechanism_controllers::BaseControllerState2 > > state_publisher_
publishes information about the caster and wheel controllers
geometry_msgs::Twist cmd_vel_
speed command vector used internally to represent the current commanded speed
void setDesiredWheelSpeeds()
sends the desired wheel speeds to the wheel controllers
ros::Time cmd_received_timestamp_
timestamp corresponding to when the command received by the node
void publishState(const ros::Time &current_time)
Publish the state.
bool new_cmd_available_
true when new command received by node
double state_publish_time_
Time interval between state publishing.


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