odom_plugin.cpp
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 #include <math.h>
21 
25 
27 
28 #include <nav_msgs/Odometry.h>
29 #include <std_srvs/Trigger.h>
30 
32 
33 #include <urdf/model.h>
35 
37 {
38 
39 // this controller gets access to the JointStateInterface
40 class OdometryController: public controller_interface::Controller<hardware_interface::JointStateInterface>
41 {
42 public:
44 
46  {
47  if (!nh.getParam("steer_joint", wheel_state_.steer_name)){
48  ROS_ERROR("Parameter 'steer_joint' not set");
49  return false;
50  }
51  if (!nh.getParam("drive_joint", wheel_state_.drive_name)){
52  ROS_ERROR("Parameter 'drive_joint' not set");
53  return false;
54  }
57 
58 
59  urdf::Model model;
60  std::string description_name;
61  bool has_model = nh.searchParam("robot_description", description_name) && model.initParam(description_name);
62 
63  urdf::Vector3 steer_pos;
64  urdf::JointConstSharedPtr steer_joint;
65 
66  if(has_model){
67  steer_joint = model.getJoint(wheel_state_.steer_name);
68  if(steer_joint){
69  tf2::Transform transform;
70  //root link for tricycle is "base_pivot_link"
71  if(parseWheelTransform(wheel_state_.steer_name, model.getRoot()->name, transform, &model)){
72  wheel_state_.pos_x = transform.getOrigin().getX();
73  wheel_state_.pos_y = transform.getOrigin().getY();
74  wheel_state_.radius = transform.getOrigin().getZ();
75  wheel_state_.sign = cos(transform.getRotation().getAngle());
76  }
77  }
78  }
79 
80  double publish_rate;
81  if (!nh.getParam("publish_rate", publish_rate)){
82  ROS_ERROR("Parameter 'publish_rate' not set");
83  return false;
84  }
85  if(publish_rate <= 0){
86  ROS_ERROR_STREAM("publish_rate must be positive.");
87  return false;
88  }
89 
90  const std::string frame_id = nh.param("frame_id", std::string("odom"));
91  const std::string child_frame_id = nh.param("child_frame_id", std::string("base_footprint"));
92  const double cov_pose = nh.param("cov_pose", 0.1);
93  const double cov_twist = nh.param("cov_twist", 0.1);
94 
95  odom_tracker_.reset(new OdometryTracker(frame_id, child_frame_id, cov_pose, cov_twist));
96  odom_ = odom_tracker_->getOdometry();
97 
98  topic_pub_odometry_ = nh.advertise<nav_msgs::Odometry>("odometry", 1);
99 
100  bool broadcast_tf = true;
101  nh.getParam("broadcast_tf", broadcast_tf);
102 
103  if(broadcast_tf){
104  odom_tf_.header.frame_id = frame_id;
105  odom_tf_.child_frame_id = child_frame_id;
107  }
108 
110  service_reset_ = nh.advertiseService("reset_odometry", &OdometryController::srv_reset, this);
111 
112  return true;
113  }
114  virtual void starting(const ros::Time& time)
115  {
116  if(time != stop_time_) odom_tracker_->init(time); // do not init odometry on restart
117  reset_ = false;
118  }
119 
120  virtual bool srv_reset(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
121  {
122  if(!isRunning()){
123  res.message = "not running";
124  res.success = false;
125  }else{
126  boost::mutex::scoped_lock lock(mutex_);
127  reset_ = true;
128  lock.unlock();
129  res.success = true;
130  ROS_INFO("Resetting odometry to zero.");
131  }
132 
133  return true;
134  }
135 
136  virtual void update(const ros::Time& time, const ros::Duration& period)
137  {
138  updateState();
139 
141 
142  boost::mutex::scoped_try_lock lock(mutex_);
143  if(lock){
144  if(reset_){
145  odom_tracker_->init(time);
146  reset_ = false;
147  }
148  odom_ = odom_tracker_->getOdometry();
149  }
150  }
151  virtual void stopping(const ros::Time& time) { stop_time_ = time; }
152 
153 private:
158 
159  ros::Publisher topic_pub_odometry_; // calculated (measured) velocity, rotation and pose (odometry-based) for the robot
160  ros::ServiceServer service_reset_; // service to reset odometry to zero
161 
162  boost::scoped_ptr<tf::TransformBroadcaster> tf_broadcast_odometry_; // according transformation for the tf broadcaster
163  boost::scoped_ptr<OdometryTracker> odom_tracker_;
165  nav_msgs::Odometry odom_;
166  bool reset_;
167  boost::mutex mutex_;
168  geometry_msgs::TransformStamped odom_tf_;
170 
171  void publish(const ros::TimerEvent&){
172  if(!isRunning()) return;
173 
174  boost::mutex::scoped_lock lock(mutex_);
175 
177 
179  // compose and publish transform for tf package
180  // compose header
181  odom_tf_.header.stamp = odom_.header.stamp;
182  // compose data container
183  odom_tf_.transform.translation.x = odom_.pose.pose.position.x;
184  odom_tf_.transform.translation.y = odom_.pose.pose.position.y;
185  odom_tf_.transform.rotation = odom_.pose.pose.orientation;
186 
187  // publish the transform (for debugging, conflicts with robot-pose-ekf)
188  tf_broadcast_odometry_->sendTransform(odom_tf_);
189  }
190  }
191 
192  void updateState(){
193  //get JointState from JointHandles
198 
199  //calculate forward kinematics
200  // http://www.wolframalpha.com/input/?i=Solve%5Bx%3D%3Dw*cos(a),+phi%3D%3Dw*sin(a)%2Fr,a,w%5D
201  double r_base = wheel_state_.pos_x * wheel_state_.sign;
203  platform_state_.velY = 0.0;
205  }
206 };
207 
208 }
209 
cob_tricycle_controller::OdometryController::init
virtual bool init(hardware_interface::JointStateInterface *hw, ros::NodeHandle &nh)
Definition: odom_plugin.cpp:45
WheelState::sign
double sign
Definition: TricycleCtrlTypes.h:47
cob_tricycle_controller::OdometryController::mutex_
boost::mutex mutex_
Definition: odom_plugin.cpp:167
cob_tricycle_controller
Definition: control_plugin.cpp:35
WheelState
Definition: TricycleCtrlTypes.h:35
cob_tricycle_controller::OdometryController::drive_joint_
hardware_interface::JointStateHandle drive_joint_
Definition: odom_plugin.cpp:157
ros::Publisher
WheelState::drive_vel
double drive_vel
Definition: TricycleCtrlTypes.h:41
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
cob_tricycle_controller::OdometryController::tf_broadcast_odometry_
boost::scoped_ptr< tf::TransformBroadcaster > tf_broadcast_odometry_
Definition: odom_plugin.cpp:162
HardwareResourceManager< JointStateHandle >::getHandle
JointStateHandle getHandle(const std::string &name)
cob_tricycle_controller::OdometryController::updateState
void updateState()
Definition: odom_plugin.cpp:192
hardware_interface::JointStateInterface
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
WheelState::drive_name
std::string drive_name
Definition: TricycleCtrlTypes.h:36
WheelState::pos_y
double pos_y
Definition: TricycleCtrlTypes.h:44
PlatformState::rotTheta
double rotTheta
Definition: TricycleCtrlTypes.h:30
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
tf2::Transform::getOrigin
TF2SIMD_FORCE_INLINE Vector3 & getOrigin()
WheelState::steer_vel
double steer_vel
Definition: TricycleCtrlTypes.h:39
OdometryTracker.h
urdf::Model
cob_tricycle_controller::OdometryController::update
virtual void update(const ros::Time &time, const ros::Duration &period)
Definition: odom_plugin.cpp:136
controller_interface::Controller
cob_tricycle_controller::OdometryController::steer_joint_
hardware_interface::JointStateHandle steer_joint_
Definition: odom_plugin.cpp:156
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
cob_tricycle_controller::OdometryController::publish
void publish(const ros::TimerEvent &)
Definition: odom_plugin.cpp:171
transform_broadcaster.h
WheelState::steer_pos
double steer_pos
Definition: TricycleCtrlTypes.h:38
WheelState::steer_name
std::string steer_name
Definition: TricycleCtrlTypes.h:36
ros::ServiceServer
cob_tricycle_controller::OdometryController::service_reset_
ros::ServiceServer service_reset_
Definition: odom_plugin.cpp:160
class_list_macros.h
controller_interface::ControllerBase
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
parseWheelTransform
bool parseWheelTransform(const std::string &joint_name, const std::string &parent_link_name, tf2::Transform &transform, urdf::Model *model)
Definition: param_parser.h:27
controller.h
tf::TransformBroadcaster
cob_tricycle_controller::OdometryController::stopping
virtual void stopping(const ros::Time &time)
Definition: odom_plugin.cpp:151
cob_tricycle_controller::OdometryController::odom_
nav_msgs::Odometry odom_
Definition: odom_plugin.cpp:165
tf2::Quaternion::getAngle
tf2Scalar getAngle() const
model.h
ros::NodeHandle::searchParam
bool searchParam(const std::string &key, std::string &result) const
hardware_interface::JointStateHandle
tf2::Transform
cob_tricycle_controller::OdometryController::OdometryController
OdometryController()
Definition: odom_plugin.cpp:43
tf2::Transform::getRotation
Quaternion getRotation() const
PlatformState::velX
double velX
Definition: TricycleCtrlTypes.h:28
ros::TimerEvent
controller_interface::ControllerBase::isRunning
bool isRunning() const
TricycleCtrlTypes.h
WheelState::pos_x
double pos_x
Definition: TricycleCtrlTypes.h:43
param_parser.h
cob_tricycle_controller::OdometryController::stop_time_
ros::Time stop_time_
Definition: odom_plugin.cpp:169
cob_tricycle_controller::OdometryController::publish_timer_
ros::Timer publish_timer_
Definition: odom_plugin.cpp:164
PlatformState::velY
double velY
Definition: TricycleCtrlTypes.h:29
cob_tricycle_controller::OdometryController::starting
virtual void starting(const ros::Time &time)
Definition: odom_plugin.cpp:114
cob_tricycle_controller::OdometryController::wheel_state_
WheelState wheel_state_
Definition: odom_plugin.cpp:155
cob_tricycle_controller::OdometryController::reset_
bool reset_
Definition: odom_plugin.cpp:166
joint_state_interface.h
cob_tricycle_controller::OdometryController::odom_tracker_
boost::scoped_ptr< OdometryTracker > odom_tracker_
Definition: odom_plugin.cpp:163
WheelState::radius
double radius
Definition: TricycleCtrlTypes.h:46
WheelState::drive_pos
double drive_pos
Definition: TricycleCtrlTypes.h:40
PlatformState
Definition: TricycleCtrlTypes.h:27
hardware_interface::JointStateHandle::getVelocity
double getVelocity() const
ros::Time
hardware_interface::JointStateHandle::getPosition
double getPosition() const
cob_tricycle_controller::OdometryController
Definition: odom_plugin.cpp:40
urdf::Model::initParam
URDF_EXPORT bool initParam(const std::string &param)
cob_tricycle_controller::OdometryController::platform_state_
PlatformState platform_state_
Definition: odom_plugin.cpp:154
ROS_ERROR
#define ROS_ERROR(...)
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
cob_tricycle_controller::OdometryController::odom_tf_
geometry_msgs::TransformStamped odom_tf_
Definition: odom_plugin.cpp:168
DurationBase< Duration >::toSec
double toSec() const
ROS_INFO
#define ROS_INFO(...)
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
OdometryTracker
ros::Duration
ros::Timer
cob_tricycle_controller::OdometryController::topic_pub_odometry_
ros::Publisher topic_pub_odometry_
Definition: odom_plugin.cpp:159
Transform.h
ros::NodeHandle
cob_tricycle_controller::OdometryController::srv_reset
virtual bool srv_reset(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Definition: odom_plugin.cpp:120


cob_tricycle_controller
Author(s): Felix Messmer
autogenerated on Mon May 1 2023 02:44:40