mecanum_drive_controller.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, PAL Robotics, S.L.
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 PAL Robotics 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 /*
36  * Author: Enrique Fernández
37  */
38 
42 
43 #include <nav_msgs/Odometry.h>
44 #include <tf/tfMessage.h>
45 
48 
51 
53 {
54 
65  : public controller_interface::Controller<hardware_interface::VelocityJointInterface>
66 {
67 public:
69 
77  ros::NodeHandle& root_nh,
78  ros::NodeHandle &controller_nh);
79 
85  void update(const ros::Time& time, const ros::Duration& period);
86 
91  void starting(const ros::Time& time);
92 
97  void stopping(const ros::Time& time);
98 
99 private:
100  std::string name_;
101 
105  bool open_loop_;
106 
112 
114  struct Commands
115  {
116  double linX;
117  double linY;
118  double ang;
120 
121  Commands() : linX(0.0), linY(0.0), ang(0.0), stamp(0.0) {}
122  };
124  Commands command_struct_;
126 
131  geometry_msgs::TransformStamped odom_frame_;
132 
135  double wheels_k_; // wheels geometric param used in mecanum wheels' ik
136  double wheels_radius_;
137  double wheel_separation_x_;
138  double wheel_separation_y_;
139 
141  double cmd_vel_timeout_;
142 
144  std::string base_frame_id_;
145  std::string odom_frame_id_;
146 
148  bool enable_odom_tf_;
149 
151  size_t wheel_joints_size_;
152 
153  // Speed limiters:
154  Commands last_cmd_;
158 
159 private:
163  void brake();
164 
169  void cmdVelCallback(const geometry_msgs::Twist& command);
170 
180  ros::NodeHandle &controller_nh,
181  const std::string& wheel0_name,
182  const std::string& wheel1_name,
183  const std::string& wheel2_name,
184  const std::string& wheel3_name);
185 
192  bool getWheelRadius(const urdf::ModelInterfaceSharedPtr model, const urdf::LinkConstSharedPtr& wheel_link, double& wheel_radius);
193 
199  void setupRtPublishersMsg(ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh);
200 
201 };
202 
204 
205 } // namespace mecanum_drive_controller
realtime_tools::RealtimeBuffer
mecanum_drive_controller::MecanumDriveController::cmd_vel_timeout_
double cmd_vel_timeout_
Timeout to consider cmd_vel commands old:
Definition: mecanum_drive_controller.h:205
realtime_publisher.h
mecanum_drive_controller::MecanumDriveController::wheel2_jointHandle_
hardware_interface::JointHandle wheel2_jointHandle_
Definition: mecanum_drive_controller.h:174
mecanum_drive_controller::MecanumDriveController::Commands::linY
double linY
Definition: mecanum_drive_controller.h:181
mecanum_drive_controller::MecanumDriveController::wheels_radius_
double wheels_radius_
Definition: mecanum_drive_controller.h:200
mecanum_drive_controller::MecanumDriveController::sub_command_
ros::Subscriber sub_command_
Definition: mecanum_drive_controller.h:189
boost::shared_ptr
mecanum_drive_controller::MecanumDriveController::limiter_linY_
SpeedLimiter limiter_linY_
Definition: mecanum_drive_controller.h:220
mecanum_drive_controller::MecanumDriveController::update
void update(const ros::Time &time, const ros::Duration &period)
Updates controller, i.e. computes the odometry and sets the new velocity commands.
Definition: mecanum_drive_controller.cpp:190
mecanum_drive_controller::MecanumDriveController::Commands::linX
double linX
Definition: mecanum_drive_controller.h:180
realtime_buffer.h
mecanum_drive_controller::MecanumDriveController::MecanumDriveController
MecanumDriveController()
Definition: mecanum_drive_controller.cpp:81
mecanum_drive_controller::MecanumDriveController::Commands::ang
double ang
Definition: mecanum_drive_controller.h:182
mecanum_drive_controller::MecanumDriveController::name_
std::string name_
Definition: mecanum_drive_controller.h:164
mecanum_drive_controller
Definition: mecanum_drive_controller.h:52
mecanum_drive_controller::MecanumDriveController::wheel_separation_y_
double wheel_separation_y_
Definition: mecanum_drive_controller.h:202
mecanum_drive_controller::MecanumDriveController::starting
void starting(const ros::Time &time)
Starts controller.
Definition: mecanum_drive_controller.cpp:279
odometry.h
controller_interface::Controller
mecanum_drive_controller::MecanumDriveController::command_struct_
Commands command_struct_
Definition: mecanum_drive_controller.h:188
mecanum_drive_controller::Odometry
The Odometry class handles odometry readings (2D pose and velocity with related timestamp)
Definition: odometry.h:92
mecanum_drive_controller::MecanumDriveController::wheel_joints_size_
size_t wheel_joints_size_
Number of wheel joints:
Definition: mecanum_drive_controller.h:215
mecanum_drive_controller::MecanumDriveController::Commands::Commands
Commands()
Definition: mecanum_drive_controller.h:185
mecanum_drive_controller::MecanumDriveController::Commands::stamp
ros::Time stamp
Definition: mecanum_drive_controller.h:183
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(RobotLocalization::EkfNodelet, nodelet::Nodelet)
mecanum_drive_controller::MecanumDriveController::limiter_linX_
SpeedLimiter limiter_linX_
Definition: mecanum_drive_controller.h:219
class_list_macros.h
mecanum_drive_controller::MecanumDriveController::wheel3_jointHandle_
hardware_interface::JointHandle wheel3_jointHandle_
Definition: mecanum_drive_controller.h:175
controller_interface::ControllerBase
mecanum_drive_controller::MecanumDriveController::init
bool init(hardware_interface::VelocityJointInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Initialize controller.
Definition: mecanum_drive_controller.cpp:97
hardware_interface::VelocityJointInterface
mecanum_drive_controller::MecanumDriveController::odometry_
Odometry odometry_
Definition: mecanum_drive_controller.h:194
mecanum_drive_controller::MecanumDriveController::setupRtPublishersMsg
void setupRtPublishersMsg(ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Sets the odometry publishing fields.
Definition: mecanum_drive_controller.cpp:508
controller.h
joint_command_interface.h
mecanum_drive_controller::MecanumDriveController::stopping
void stopping(const ros::Time &time)
Stops controller.
Definition: mecanum_drive_controller.cpp:290
mecanum_drive_controller::SpeedLimiter
Definition: speed_limiter.h:77
mecanum_drive_controller::MecanumDriveController::setWheelParamsFromUrdf
bool setWheelParamsFromUrdf(ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, const std::string &wheel0_name, const std::string &wheel1_name, const std::string &wheel2_name, const std::string &wheel3_name)
Sets odometry parameters from the URDF, i.e. the wheel radius and separation.
Definition: mecanum_drive_controller.cpp:328
mecanum_drive_controller::MecanumDriveController::cmdVelCallback
void cmdVelCallback(const geometry_msgs::Twist &command)
Velocity command callback.
Definition: mecanum_drive_controller.cpp:305
mecanum_drive_controller::MecanumDriveController::enable_odom_tf_
bool enable_odom_tf_
Whether to publish odometry to tf or not:
Definition: mecanum_drive_controller.h:212
mecanum_drive_controller::MecanumDriveController::wheels_k_
double wheels_k_
Definition: mecanum_drive_controller.h:199
mecanum_drive_controller::MecanumDriveController::last_cmd_
Commands last_cmd_
Definition: mecanum_drive_controller.h:218
mecanum_drive_controller::MecanumDriveController::last_state_publish_time_
ros::Time last_state_publish_time_
Definition: mecanum_drive_controller.h:168
mecanum_drive_controller::MecanumDriveController::odom_pub_
boost::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odom_pub_
Odometry related:
Definition: mecanum_drive_controller.h:192
mecanum_drive_controller::MecanumDriveController::wheel_separation_x_
double wheel_separation_x_
Definition: mecanum_drive_controller.h:201
mecanum_drive_controller::MecanumDriveController::odom_frame_id_
std::string odom_frame_id_
Definition: mecanum_drive_controller.h:209
mecanum_drive_controller::MecanumDriveController::wheel0_jointHandle_
hardware_interface::JointHandle wheel0_jointHandle_
Hardware handles:
Definition: mecanum_drive_controller.h:172
hardware_interface::JointHandle
ros::Time
mecanum_drive_controller::MecanumDriveController::open_loop_
bool open_loop_
Definition: mecanum_drive_controller.h:169
mecanum_drive_controller::MecanumDriveController::getWheelRadius
bool getWheelRadius(const urdf::ModelInterfaceSharedPtr model, const urdf::LinkConstSharedPtr &wheel_link, double &wheel_radius)
Get the radius of a given wheel.
Definition: mecanum_drive_controller.cpp:468
mecanum_drive_controller::MecanumDriveController::base_frame_id_
std::string base_frame_id_
Frame to use for the robot base:
Definition: mecanum_drive_controller.h:208
speed_limiter.h
mecanum_drive_controller::MecanumDriveController::odom_frame_
geometry_msgs::TransformStamped odom_frame_
Definition: mecanum_drive_controller.h:195
mecanum_drive_controller::MecanumDriveController::limiter_ang_
SpeedLimiter limiter_ang_
Definition: mecanum_drive_controller.h:221
mecanum_drive_controller::MecanumDriveController::brake
void brake()
Brakes the wheels, i.e. sets the velocity to 0.
Definition: mecanum_drive_controller.cpp:296
mecanum_drive_controller::MecanumDriveController::command_
realtime_tools::RealtimeBuffer< Commands > command_
Definition: mecanum_drive_controller.h:187
mecanum_drive_controller::MecanumDriveController::tf_odom_pub_
boost::shared_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > tf_odom_pub_
Definition: mecanum_drive_controller.h:193
ros::Duration
mecanum_drive_controller::MecanumDriveController::use_realigned_roller_joints_
bool use_realigned_roller_joints_
Wheel radius (assuming it's the same for the left and right wheels):
Definition: mecanum_drive_controller.h:198
mecanum_drive_controller::MecanumDriveController
Definition: mecanum_drive_controller.h:96
mecanum_drive_controller::MecanumDriveController::publish_period_
ros::Duration publish_period_
Odometry related:
Definition: mecanum_drive_controller.h:167
mecanum_drive_controller::MecanumDriveController::wheel1_jointHandle_
hardware_interface::JointHandle wheel1_jointHandle_
Definition: mecanum_drive_controller.h:173
ros::NodeHandle
ros::Subscriber


ridgeback_control
Author(s): Mike Purvis
autogenerated on Wed Jul 24 2024 02:57:39