WheelControllerBase.h
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #ifndef H_WHEEL_CONTROLLER_IMPL
19 #define H_WHEEL_CONTROLLER_IMPL
20 
23 
25 
27 #include <geometry_msgs/Twist.h>
28 
29 #include <boost/scoped_ptr.hpp>
30 #include <boost/weak_ptr.hpp>
31 #include <boost/thread/mutex.hpp>
32 
34 #include <cob_base_controller_utils/WheelCommands.h>
35 
37 {
38 
39 template<typename T> class WheelControllerBase: public T
40 {
41 public:
42  bool setup(ros::NodeHandle &root_nh, ros::NodeHandle& controller_nh){
43  controller_nh.param("max_rot_velocity", max_vel_rot_, 0.0);
44  if(max_vel_rot_ < 0){
45  ROS_ERROR_STREAM("max_rot_velocity must be non-negative.");
46  return false;
47  }
48  controller_nh.param("max_trans_velocity", max_vel_trans_, 0.0);
49  if(max_vel_trans_ < 0){
50  ROS_ERROR_STREAM("max_trans_velocity must be non-negative.");
51  return false;
52  }
53  double timeout;
54  controller_nh.param("timeout", timeout, 1.0);
55  if(timeout < 0){
56  ROS_ERROR_STREAM("timeout must be non-negative.");
57  return false;
58  }
59  timeout_.fromSec(timeout);
60 
61  pub_divider_ = controller_nh.param("pub_divider",0);
62 
63  wheel_commands_.resize(this->wheel_states_.size());
64  twist_subscriber_ = controller_nh.subscribe("command", 1, &WheelControllerBase::topicCallbackTwistCmd, this);
65 
67 
68  commands_pub_->msg_.drive_target_velocity.resize(this->wheel_states_.size());
69  commands_pub_->msg_.steer_target_velocity.resize(this->wheel_states_.size());
70  commands_pub_->msg_.steer_target_position.resize(this->wheel_states_.size());
71  commands_pub_->msg_.steer_target_error.resize(this->wheel_states_.size());
72 
73  return true;
74  }
75  virtual void starting(const ros::Time& time){
76  this->geom_->reset();
77  target_.updated = false;
78  cycles_ = 0;
79  }
80  void updateCtrl(const ros::Time& time, const ros::Duration& period){
81  {
82  boost::mutex::scoped_try_lock lock(mutex_);
83  if(lock){
84  Target target = target_;
85  target_.updated = false;
86 
87  if(!target.stamp.isZero() && !timeout_.isZero() && (time - target.stamp) > timeout_){
88  target_.stamp = ros::Time(); // only reset once
89  target.state = PlatformState();
90  target.updated = true;
91  }
92  lock.unlock();
93 
94  if(target.updated){
95  this->geom_->setTarget(target.state);
96  }
97  }
98  }
99 
100  this->geom_->calcControlStep(wheel_commands_, period.toSec(), false);
101 
102  if(cycles_ < pub_divider_ && (++cycles_) == pub_divider_){
103  if(commands_pub_->trylock()){
104  ++(commands_pub_->msg_.header.seq);
105  commands_pub_->msg_.header.stamp = time;
106 
107  for (unsigned i=0; i<wheel_commands_.size(); i++){
108  commands_pub_->msg_.drive_target_velocity[i] = wheel_commands_[i].dVelGearDriveRadS;
109  commands_pub_->msg_.steer_target_velocity[i] = wheel_commands_[i].dVelGearSteerRadS;
110  commands_pub_->msg_.steer_target_position[i] = wheel_commands_[i].dAngGearSteerRad;
111  commands_pub_->msg_.steer_target_error[i] = wheel_commands_[i].dAngGearSteerRadDelta;
112  }
113  commands_pub_->unlockAndPublish();
114 
115  }
116  cycles_ = 0;
117  }
118  }
119  virtual void stopping(const ros::Time& time) {}
120 
121 protected:
122  struct Target {
124  bool updated;
126  } target_;
127 
128  std::vector<WheelCommand> wheel_commands_;
129 
130  boost::mutex mutex_;
132 
133  boost::scoped_ptr<realtime_tools::RealtimePublisher<cob_base_controller_utils::WheelCommands> > commands_pub_;
134  uint32_t cycles_;
135  uint32_t pub_divider_;
136 
139 
140  void topicCallbackTwistCmd(const geometry_msgs::Twist::ConstPtr& msg){
141  if(this->isRunning()){
142  boost::mutex::scoped_lock lock(mutex_);
143  if(isnan(msg->linear.x) || isnan(msg->linear.y) || isnan(msg->angular.z)) {
144  ROS_FATAL("Received NaN-value in Twist message. Reset target to zero.");
146  }else{
147  target_.state.setVelX(limitValue(msg->linear.x, max_vel_trans_));
148  target_.state.setVelY(limitValue(msg->linear.y, max_vel_trans_));
149  target_.state.dRotRobRadS = limitValue(msg->angular.z, max_vel_rot_);
150  }
151  target_.updated = true;
153  }
154  }
155 
156 
157 };
158 
159 }
160 #endif
void setVelY(const double val)
#define ROS_FATAL(...)
bool setup(ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
virtual void starting(const ros::Time &time)
void topicCallbackTwistCmd(const geometry_msgs::Twist::ConstPtr &msg)
boost::scoped_ptr< realtime_tools::RealtimePublisher< cob_base_controller_utils::WheelCommands > > commands_pub_
Duration & fromSec(double t)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
double limitValue(double value, double limit)
static Time now()
virtual void stopping(const ros::Time &time)
#define ROS_ERROR_STREAM(args)
void setVelX(const double val)
void updateCtrl(const ros::Time &time, const ros::Duration &period)
struct cob_omni_drive_controller::WheelControllerBase::Target target_


cob_omni_drive_controller
Author(s): Christian Connette, Mathias Lüdtke
autogenerated on Thu Apr 8 2021 02:39:52