pr2_base_controller.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 
40 
42 
43 namespace controller {
44 
45  const static double EPS = 1e-5;
46 
48 {
49  //init variables
50  cmd_vel_.linear.x = 0;
51  cmd_vel_.linear.y = 0;
52  cmd_vel_.angular.z = 0;
53 
54  desired_vel_.linear.x = 0;
55  desired_vel_.linear.y = 0;
56  desired_vel_.angular.z = 0;
57 
58  cmd_vel_t_.linear.x = 0;
59  cmd_vel_t_.linear.y = 0;
60  cmd_vel_t_.angular.z = 0;
61 
62  new_cmd_available_ = false;
64 
65  pthread_mutex_init(&pr2_base_controller_lock_, NULL);
66 }
67 
69 {
72 }
73 
75 {
76  if(!base_kin_.init(robot,n))
77  return false;
78  node_ = n;
80 
81  int num_joints = base_kin_.num_wheels_ + base_kin_.num_casters_;
82  state_publisher_->msg_.joint_names.resize(num_joints);
83  state_publisher_->msg_.joint_velocity_measured.resize(num_joints);
84  state_publisher_->msg_.joint_effort_measured.resize(num_joints);
85  state_publisher_->msg_.joint_velocity_commanded.resize(num_joints);
86  state_publisher_->msg_.joint_effort_commanded.resize(num_joints);
87  state_publisher_->msg_.joint_velocity_error.resize(num_joints);
88  state_publisher_->msg_.joint_effort_error.resize(num_joints);
89 
90  //Get params from param server
91  node_.param<double> ("max_translational_velocity", max_translational_velocity_,0.5);
92  node_.param<double> ("max_rotational_velocity", max_rotational_velocity_, 10.0); //0.5
93  node_.param<double> ("max_translational_acceleration/x", max_accel_.linear.x, .2);
94  node_.param<double> ("max_translational_acceleration/y", max_accel_.linear.y, .2);
95  node_.param<double> ("max_rotational_acceleration", max_accel_.angular.z, 10.0); //0.2
96 
97  node_.param<double> ("kp_caster_steer", kp_caster_steer_, 80.0);
98  node_.param<double> ("timeout", timeout_, 1.0);
99  node_.param<double> ("state_publish_rate", state_publish_rate_,2.0);
101  {
102  publish_state_ = false;
103  state_publish_time_ = 0.0;
104  }
105  else
106  {
107  publish_state_ = true;
109  }
110 
111  // cmd_sub_deprecated_ = root_handle_.subscribe<geometry_msgs::Twist>("cmd_vel", 1, &Pr2BaseController::commandCallback, this);
112  cmd_sub_ = node_.subscribe<geometry_msgs::Twist>("command", 1, &Pr2BaseController::commandCallback, this);
113 
114  //casters
117  for(int i = 0; i < base_kin_.num_casters_; i++)
118  {
119  control_toolbox::Pid p_i_d;
120  state_publisher_->msg_.joint_names[i] = base_kin_.caster_[i].joint_name_;
121  if(!p_i_d.init(ros::NodeHandle(node_, base_kin_.caster_[i].joint_name_+"/velocity_controller")))
122  {
123  ROS_ERROR("Could not initialize pid for %s",base_kin_.caster_[i].joint_name_.c_str());
124  return false;
125  }
126 
127  if(!caster_position_pid_[i].init(ros::NodeHandle(node_, base_kin_.caster_[i].joint_name_+"/position_controller")))
128  {
129  ROS_ERROR("Could not initialize position pid controller for %s",base_kin_.caster_[i].joint_name_.c_str());
130  return false;
131  }
132  caster_controller_[i].reset(new JointVelocityController());
133  if(!caster_controller_[i]->init(base_kin_.robot_state_, base_kin_.caster_[i].joint_name_, p_i_d))
134  {
135  ROS_ERROR("Could not initialize pid for %s",base_kin_.caster_[i].joint_name_.c_str());
136  return false;
137  }
138  if (!caster_controller_[i]->joint_state_->calibrated_)
139  {
140  ROS_ERROR("Caster joint \"%s\" not calibrated (namespace: %s)",
141  base_kin_.caster_[i].joint_name_.c_str(), node_.getNamespace().c_str());
142  return false;
143  }
144  }
145  //wheels
147  for(int j = 0; j < base_kin_.num_wheels_; j++)
148  {
149  control_toolbox::Pid p_i_d;
150  state_publisher_->msg_.joint_names[j + base_kin_.num_casters_] = base_kin_.wheel_[j].joint_name_;
151  if(!p_i_d.init(ros::NodeHandle(node_,base_kin_.wheel_[j].joint_name_)))
152  {
153  ROS_ERROR("Could not initialize pid for %s",base_kin_.wheel_[j].joint_name_.c_str());
154  return false;
155  }
156  wheel_controller_[j].reset(new JointVelocityController());
157  if(!wheel_controller_[j]->init(base_kin_.robot_state_, base_kin_.wheel_[j].joint_name_, p_i_d))
158  {
159  ROS_ERROR("Could not initialize joint velocity controller for %s",base_kin_.wheel_[j].joint_name_.c_str());
160  return false;
161  }
162  }
163  for(int i = 0; i < base_kin_.num_casters_; ++i)
164  {
165  if(!base_kin_.caster_[i].joint_->calibrated_)
166  {
167  ROS_ERROR("The Base controller could not start because the casters were not calibrated. Relaunch the base controller after you see the caster calibration finish.");
168  return false; // Casters are not calibrated
169  }
170  }
171 
172  if (!((filters::MultiChannelFilterBase<double>&)caster_vel_filter_).configure(base_kin_.num_casters_, std::string("caster_velocity_filter"), node_)){
173  ROS_ERROR("BaseController: could not configure velocity filters for casters");
174  return false;
175  }
177  return true;
178 }
179 
180 // Set the base velocity command
181 void Pr2BaseController::setCommand(const geometry_msgs::Twist &cmd_vel)
182 {
183  double vel_mag = sqrt(cmd_vel.linear.x * cmd_vel.linear.x + cmd_vel.linear.y * cmd_vel.linear.y);
184  double clamped_vel_mag = filters::clamp(vel_mag,-max_translational_velocity_, max_translational_velocity_);
185  if(vel_mag > EPS)
186  {
187  cmd_vel_t_.linear.x = cmd_vel.linear.x * clamped_vel_mag / vel_mag;
188  cmd_vel_t_.linear.y = cmd_vel.linear.y * clamped_vel_mag / vel_mag;
189  }
190  else
191  {
192  cmd_vel_t_.linear.x = 0.0;
193  cmd_vel_t_.linear.y = 0.0;
194  }
197 
198  ROS_DEBUG("BaseController:: command received: %f %f %f",cmd_vel.linear.x,cmd_vel.linear.y,cmd_vel.angular.z);
199  ROS_DEBUG("BaseController:: command current: %f %f %f", cmd_vel_.linear.x,cmd_vel_.linear.y,cmd_vel_.angular.z);
200  ROS_DEBUG("BaseController:: clamped vel: %f", clamped_vel_mag);
201  ROS_DEBUG("BaseController:: vel: %f", vel_mag);
202 
203  for(int i=0; i < (int) base_kin_.num_wheels_; i++)
204  {
205  ROS_DEBUG("BaseController:: wheel speed cmd:: %d %f",i,(base_kin_.wheel_[i].direction_multiplier_*base_kin_.wheel_[i].wheel_speed_cmd_));
206  }
207  for(int i=0; i < (int) base_kin_.num_casters_; i++)
208  {
209  ROS_DEBUG("BaseController:: caster speed cmd:: %d %f",i,(base_kin_.caster_[i].steer_velocity_desired_));
210  }
211  new_cmd_available_ = true;
212 }
213 
214 geometry_msgs::Twist Pr2BaseController::interpolateCommand(const geometry_msgs::Twist &start, const geometry_msgs::Twist &end, const geometry_msgs::Twist &max_rate, const double &dT)
215 {
216  geometry_msgs::Twist result;
217  geometry_msgs::Twist alpha;
218  double delta(0), max_delta(0);
219 
220  delta = end.linear.x - start.linear.x;
221  max_delta = max_rate.linear.x * dT;
222  if(fabs(delta) <= max_delta || max_delta < EPS)
223  alpha.linear.x = 1;
224  else
225  alpha.linear.x = max_delta / fabs(delta);
226 
227  delta = end.linear.y - start.linear.y;
228  max_delta = max_rate.linear.y * dT;
229  if(fabs(delta) <= max_delta || max_delta < EPS)
230  alpha.linear.y = 1;
231  else
232  alpha.linear.y = max_delta / fabs(delta);
233 
234  delta = end.angular.z - start.angular.z;
235  max_delta = max_rate.angular.z * dT;
236  if(fabs(delta) <= max_delta || max_delta < EPS)
237  alpha.angular.z = 1;
238  else
239  alpha.angular.z = max_delta / fabs(delta);
240 
241  double alpha_min = alpha.linear.x;
242  if(alpha.linear.y < alpha_min)
243  alpha_min = alpha.linear.y;
244  if(alpha.angular.z < alpha_min)
245  alpha_min = alpha.angular.z;
246 
247  result.linear.x = start.linear.x + alpha_min * (end.linear.x - start.linear.x);
248  result.linear.y = start.linear.y + alpha_min * (end.linear.y - start.linear.y);
249  result.angular.z = start.angular.z + alpha_min * (end.angular.z - start.angular.z);
250  return result;
251 }
252 
253 geometry_msgs::Twist Pr2BaseController::getCommand()// Return the current velocity command
254 {
255  geometry_msgs::Twist cmd_vel;
256  pthread_mutex_lock(&pr2_base_controller_lock_);
257  cmd_vel.linear.x = cmd_vel_.linear.x;
258  cmd_vel.linear.y = cmd_vel_.linear.y;
259  cmd_vel.angular.z = cmd_vel_.angular.z;
260  pthread_mutex_unlock(&pr2_base_controller_lock_);
261  return cmd_vel;
262 }
263 
265 {
268  for(int i = 0; i < base_kin_.num_casters_; i++)
269  {
270  caster_controller_[i]->starting();
271  }
272  for(int j = 0; j < base_kin_.num_wheels_; j++)
273  {
274  wheel_controller_[j]->starting();
275  }
276 }
277 
279 {
280  ros::Time current_time = base_kin_.robot_state_->getTime();
281  double dT = std::min<double>((current_time - last_time_).toSec(), base_kin_.MAX_DT_);
282 
284  {
285  if(pthread_mutex_trylock(&pr2_base_controller_lock_) == 0)
286  {
287  desired_vel_.linear.x = cmd_vel_t_.linear.x;
288  desired_vel_.linear.y = cmd_vel_t_.linear.y;
289  desired_vel_.angular.z = cmd_vel_t_.angular.z;
290  new_cmd_available_ = false;
291  pthread_mutex_unlock(&pr2_base_controller_lock_);
292  }
293  }
294 
295  if((current_time - cmd_received_timestamp_).toSec() > timeout_)
296  {
297  cmd_vel_.linear.x = 0;
298  cmd_vel_.linear.y = 0;
299  cmd_vel_.angular.z = 0;
300  }
301  else
303 
305 
307 
309 
311  publishState(current_time);
312 
313  last_time_ = current_time;
314 
315 }
316 
318 {
319  if((time - last_publish_time_).toSec() < state_publish_time_)
320  {
321  return;
322  }
323 
324  if(state_publisher_->trylock())
325  {
326  state_publisher_->msg_.command.linear.x = cmd_vel_.linear.x;
327  state_publisher_->msg_.command.linear.y = cmd_vel_.linear.y;
328  state_publisher_->msg_.command.angular.z = cmd_vel_.angular.z;
329 
330  for(int i = 0; i < base_kin_.num_casters_; i++)
331  {
332  state_publisher_->msg_.joint_names[i] = base_kin_.caster_[i].joint_name_;
333  state_publisher_->msg_.joint_velocity_measured[i] = base_kin_.caster_[i].joint_->velocity_;
334  state_publisher_->msg_.joint_velocity_commanded[i]= base_kin_.caster_[i].steer_velocity_desired_;
335  state_publisher_->msg_.joint_velocity_error[i] = base_kin_.caster_[i].joint_->velocity_ - base_kin_.caster_[i].steer_velocity_desired_;
336 
337  state_publisher_->msg_.joint_effort_measured[i] = base_kin_.caster_[i].joint_->measured_effort_;
338  state_publisher_->msg_.joint_effort_commanded[i] = base_kin_.caster_[i].joint_->commanded_effort_;
339  state_publisher_->msg_.joint_effort_error[i] = base_kin_.caster_[i].joint_->measured_effort_ - base_kin_.caster_[i].joint_->commanded_effort_;
340  }
341  for(int i = 0; i < base_kin_.num_wheels_; i++)
342  {
343  state_publisher_->msg_.joint_names[i+base_kin_.num_casters_] = base_kin_.wheel_[i].joint_name_;
344  state_publisher_->msg_.joint_velocity_measured[i+base_kin_.num_casters_] = base_kin_.wheel_[i].wheel_speed_actual_;
345  state_publisher_->msg_.joint_velocity_commanded[i+base_kin_.num_casters_]= base_kin_.wheel_[i].wheel_speed_error_;
346  state_publisher_->msg_.joint_velocity_error[i+base_kin_.num_casters_] = base_kin_.wheel_[i].wheel_speed_cmd_;
347 
348  state_publisher_->msg_.joint_effort_measured[i+base_kin_.num_casters_] = base_kin_.wheel_[i].joint_->measured_effort_;
349  state_publisher_->msg_.joint_effort_commanded[i+base_kin_.num_casters_] = base_kin_.wheel_[i].joint_->commanded_effort_;
350  state_publisher_->msg_.joint_effort_error[i+base_kin_.num_casters_] = base_kin_.wheel_[i].joint_->measured_effort_ - base_kin_.wheel_[i].joint_->commanded_effort_;
351  }
352  state_publisher_->unlockAndPublish();
353  last_publish_time_ = time;
354  }
355 }
356 
357 void Pr2BaseController::computeJointCommands(const double &dT)
358 {
360 
362 
364 }
365 
367 {
369 
371 }
372 
374 {
375  geometry_msgs::Twist result;
376 
377  double steer_angle_desired(0.0), steer_angle_desired_m_pi(0.0);
378  double error_steer(0.0), error_steer_m_pi(0.0);
379  double trans_vel = sqrt(cmd_vel_.linear.x * cmd_vel_.linear.x + cmd_vel_.linear.y * cmd_vel_.linear.y);
380 
381  for(int i = 0; i < base_kin_.num_casters_; i++)
382  {
383  filtered_velocity_[i] = 0.0 - base_kin_.caster_[i].joint_->velocity_;
384  }
386 
387  for(int i = 0; i < base_kin_.num_casters_; i++)
388  {
390  if(trans_vel < EPS && fabs(cmd_vel_.angular.z) < EPS)
391  {
392  steer_angle_desired = base_kin_.caster_[i].steer_angle_stored_;
393  }
394  else
395  {
396  steer_angle_desired = atan2(result.linear.y, result.linear.x);
397  base_kin_.caster_[i].steer_angle_stored_ = steer_angle_desired;
398  }
399  steer_angle_desired_m_pi = angles::normalize_angle(steer_angle_desired + M_PI);
400  error_steer = angles::shortest_angular_distance(
401  base_kin_.caster_[i].joint_->position_,
402  steer_angle_desired);
403  error_steer_m_pi = angles::shortest_angular_distance(
404  base_kin_.caster_[i].joint_->position_,
405  steer_angle_desired_m_pi);
406 
407  if(fabs(error_steer_m_pi) < fabs(error_steer))
408  {
409  error_steer = error_steer_m_pi;
410  steer_angle_desired = steer_angle_desired_m_pi;
411  }
412  // base_kin_.caster_[i].steer_velocity_desired_ = -kp_caster_steer_ * error_steer;
413  base_kin_.caster_[i].steer_velocity_desired_ = caster_position_pid_[i].computeCommand(
414  error_steer,
416  ros::Duration(dT));
417  base_kin_.caster_[i].caster_position_error_ = error_steer;
418  }
419 }
420 
422 {
423  for(int i = 0; i < base_kin_.num_casters_; i++)
424  {
425  caster_controller_[i]->setCommand(base_kin_.caster_[i].steer_velocity_desired_);
426  }
427 }
428 
430 {
431  geometry_msgs::Twist wheel_point_velocity;
432  geometry_msgs::Twist wheel_point_velocity_projected;
433  geometry_msgs::Twist wheel_caster_steer_component;
434  geometry_msgs::Twist caster_2d_velocity;
435 
436  caster_2d_velocity.linear.x = 0;
437  caster_2d_velocity.linear.y = 0;
438  caster_2d_velocity.angular.z = 0;
439 
440  double steer_angle_actual = 0;
441  for(int i = 0; i < (int) base_kin_.num_wheels_; i++)
442  {
443  base_kin_.wheel_[i].updatePosition();
444  caster_2d_velocity.angular.z = base_kin_.wheel_[i].parent_->steer_velocity_desired_;
445  steer_angle_actual = base_kin_.wheel_[i].parent_->joint_->position_;
446  wheel_point_velocity = base_kin_.pointVel2D(base_kin_.wheel_[i].position_, cmd_vel_);
447  wheel_caster_steer_component = base_kin_.pointVel2D(base_kin_.wheel_[i].offset_, caster_2d_velocity);
448 
449  double costh = cos(-steer_angle_actual);
450  double sinth = sin(-steer_angle_actual);
451 
452  wheel_point_velocity_projected.linear.x = costh * wheel_point_velocity.linear.x - sinth * wheel_point_velocity.linear.y;
453  wheel_point_velocity_projected.linear.y = sinth * wheel_point_velocity.linear.x + costh * wheel_point_velocity.linear.y;
454  base_kin_.wheel_[i].wheel_speed_cmd_ = (wheel_point_velocity_projected.linear.x + wheel_caster_steer_component.linear.x) / (base_kin_.wheel_[i].wheel_radius_);
455  }
456 }
457 
459 {
460  for(int i = 0; i < (int) base_kin_.num_wheels_; i++)
461  {
462  wheel_controller_[i]->setCommand(base_kin_.wheel_[i].direction_multiplier_ * base_kin_.wheel_[i].wheel_speed_cmd_);
463  }
464 }
465 
467 {
468  for(int i = 0; i < base_kin_.num_wheels_; i++)
470  for(int i = 0; i < base_kin_.num_casters_; i++)
472 }
473 
474 void Pr2BaseController::commandCallback(const geometry_msgs::TwistConstPtr& msg)
475 {
476  pthread_mutex_lock(&pr2_base_controller_lock_);
477  base_vel_msg_ = *msg;
478  this->setCommand(base_vel_msg_);
479  pthread_mutex_unlock(&pr2_base_controller_lock_);
480 }
481 } // namespace
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
angles::shortest_angular_distance
static double shortest_angular_distance(double from, double to)
controller::Pr2BaseController::publish_state_
bool publish_state_
Definition: pr2_base_controller.h:311
msg
msg
controller::Pr2BaseController::computeDesiredCasterSteer
void computeDesiredCasterSteer(const double &dT)
computes the desired caster speeds given the desired base speed
Definition: pr2_base_controller.cpp:405
i
int i
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
Definition: pr2_base_controller.h:86
controller::Pr2BaseController::~Pr2BaseController
~Pr2BaseController()
Destructor of the Pr2BaseController class.
Definition: pr2_base_controller.cpp:100
ROS_DEBUG
#define ROS_DEBUG(...)
controller::Pr2BaseController::setDesiredCasterSteer
void setDesiredCasterSteer()
set the desired caster steer
Definition: pr2_base_controller.cpp:453
filters::MultiChannelTransferFunctionFilter::update
virtual bool update(const std::vector< T > &data_in, std::vector< T > &data_out)
ros::Subscriber::shutdown
void shutdown()
angles::normalize_angle
def normalize_angle(angle)
controller::Pr2BaseController::max_rotational_velocity_
double max_rotational_velocity_
maximum rotational velocity magnitude allowable
Definition: pr2_base_controller.h:213
controller::BaseKinematics::caster_
std::vector< Caster > caster_
vector of every caster attached to the base
Definition: base_kinematics.h:309
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
controller::BaseKinematics::wheel_
std::vector< Wheel > wheel_
vector of every wheel attached to the base
Definition: base_kinematics.h:304
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
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
realtime_tools::RealtimePublisher
controller::Pr2BaseController::state_publish_time_
double state_publish_time_
Time interval between state publishing.
Definition: pr2_base_controller.h:293
controller::BaseKinematics::num_wheels_
int num_wheels_
number of wheels connected to the base
Definition: base_kinematics.h:294
controller
pr2_mechanism_model::RobotState
control_toolbox::Pid::init
bool init(const ros::NodeHandle &n, const bool quiet=false)
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::Pr2BaseController::computeJointCommands
void computeJointCommands(const double &dT)
computes the desired caster steers and wheel speeds
Definition: pr2_base_controller.cpp:389
ROS_ERROR
#define ROS_ERROR(...)
controller::BaseKinematics::MAX_DT_
double MAX_DT_
maximum dT used in computation of interpolated velocity command
Definition: base_kinematics.h:329
filters::clamp
static const T & clamp(const T &a, const T &b, const T &c)
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(my_controller_ns::MyControllerClass, pr2_controller_interface::Controller)
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
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
filters::MultiChannelFilterBase
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::EPS
const static double EPS
Definition: pr2_base_controller.cpp:77
pr2_controller_interface::Controller
controller::Pr2BaseController::updateJointControllers
void updateJointControllers()
tells the wheel and caster controllers to update their speeds
Definition: pr2_base_controller.cpp:498
start
ROSCPP_DECL void start()
controller::BaseKinematics::robot_state_
pr2_mechanism_model::RobotState * robot_state_
remembers everything about the state of the robot
Definition: base_kinematics.h:289
pr2_mechanism_model::RobotState::getTime
ros::Time getTime()
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
class_list_macros.hpp
controller::BaseKinematics::name_
std::string name_
name of this BaseKinematics (generally associated with whatever controller is using it)
Definition: base_kinematics.h:324
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
control_toolbox::Pid
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
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
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
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
ros::Duration
controller::BaseKinematics::num_casters_
int num_casters_
number of casters connected to the base
Definition: base_kinematics.h:299
controller::Pr2BaseController::update
void update()
(a) Updates commands to caster and wheels. Called every timestep in realtime
Definition: pr2_base_controller.cpp:310
controller::BaseKinematics::computeWheelPositions
void computeWheelPositions()
Computes 2d postion of every wheel relative to the center of the base.
Definition: base_kinematics.cpp:220
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
pr2_base_controller.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