diffbot.h
Go to the documentation of this file.
1 // Copyright (C) 2013, PAL Robotics S.L.
3 //
4 // Redistribution and use in source and binary forms, with or without
5 // modification, are permitted provided that the following conditions are met:
6 // * Redistributions of source code must retain the above copyright notice,
7 // this list of conditions and the following disclaimer.
8 // * Redistributions in binary form must reproduce the above copyright
9 // notice, this list of conditions and the following disclaimer in the
10 // documentation and/or other materials provided with the distribution.
11 // * Neither the name of PAL Robotics, Inc. nor the names of its
12 // contributors may be used to endorse or promote products derived from
13 // this software without specific prior written permission.
14 //
15 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25 // POSSIBILITY OF SUCH DAMAGE.
27 
28 // NOTE: The contents of this file have been taken largely from the ros_control wiki tutorials
29 
30 #pragma once
31 
32 
33 // ROS
34 #include <ros/ros.h>
35 #include <std_srvs/Empty.h>
36 
37 // ros_control
38 #include <controller_manager/controller_manager.h>
43 
44 // NaN
45 #include <limits>
46 
47 // ostringstream
48 #include <sstream>
49 
50 template <unsigned int NUM_JOINTS = 2>
52 {
53 public:
55  : running_(true)
58  {
59  // Intialize raw data
60  std::fill_n(pos_, NUM_JOINTS, 0.0);
61  std::fill_n(vel_, NUM_JOINTS, 0.0);
62  std::fill_n(eff_, NUM_JOINTS, 0.0);
63  std::fill_n(cmd_, NUM_JOINTS, 0.0);
64 
65  // Connect and register the joint state and velocity interface
66  for (unsigned int i = 0; i < NUM_JOINTS; ++i)
67  {
68  std::ostringstream os;
69  os << "wheel_" << i << "_joint";
70 
71  hardware_interface::JointStateHandle state_handle(os.str(), &pos_[i], &vel_[i], &eff_[i]);
73 
76  }
77 
80  }
81 
82  ros::Time getTime() const {return ros::Time::now();}
83  ros::Duration getPeriod() const {return ros::Duration(0.01);}
84 
85  void read()
86  {
87  // Read the joint state of the robot into the hardware interface
88  if (running_)
89  {
90  for (unsigned int i = 0; i < NUM_JOINTS; ++i)
91  {
92  // Note that pos_[i] will be NaN for one more cycle after we start(),
93  // but that is consistent with the knowledge we have about the state
94  // of the robot.
95  pos_[i] += vel_[i]*getPeriod().toSec(); // update position
96  vel_[i] = cmd_[i]; // might add smoothing here later
97  }
98  }
99  else
100  {
101  std::fill_n(pos_, NUM_JOINTS, std::numeric_limits<double>::quiet_NaN());
102  std::fill_n(vel_, NUM_JOINTS, std::numeric_limits<double>::quiet_NaN());
103  }
104  }
105 
106  void write()
107  {
108  // Write the commands to the joints
109  std::ostringstream os;
110  for (unsigned int i = 0; i < NUM_JOINTS - 1; ++i)
111  {
112  os << cmd_[i] << ", ";
113  }
114  os << cmd_[NUM_JOINTS - 1];
115 
116  ROS_INFO_STREAM("Commands for joints: " << os.str());
117  }
118 
119  bool start_callback(std_srvs::Empty::Request& /*req*/, std_srvs::Empty::Response& /*res*/)
120  {
121  running_ = true;
122  return true;
123  }
124 
125  bool stop_callback(std_srvs::Empty::Request& /*req*/, std_srvs::Empty::Response& /*res*/)
126  {
127  running_ = false;
128  return true;
129  }
130 
131 private:
134  double cmd_[NUM_JOINTS];
135  double pos_[NUM_JOINTS];
136  double vel_[NUM_JOINTS];
137  double eff_[NUM_JOINTS];
138  bool running_;
139 
143 };
HardwareResourceManager< JointStateHandle >::getHandle
JointStateHandle getHandle(const std::string &name)
hardware_interface::JointStateInterface
Diffbot::nh_
ros::NodeHandle nh_
Definition: diffbot.h:140
Diffbot::jnt_state_interface_
hardware_interface::JointStateInterface jnt_state_interface_
Definition: diffbot.h:132
ros.h
realtime_buffer.h
hardware_interface::InterfaceManager::registerInterface
void registerInterface(T *iface)
Diffbot::getTime
ros::Time getTime() const
Definition: diffbot.h:82
Diffbot::jnt_vel_interface_
hardware_interface::VelocityJointInterface jnt_vel_interface_
Definition: diffbot.h:133
ros::ServiceServer
hardware_interface::VelocityJointInterface
Diffbot::write
void write()
Definition: diffbot.h:106
joint_command_interface.h
advertiseService
ServiceServer advertiseService(ros::NodeHandle n, std::string name, boost::function< bool(const typename ActionSpec::_action_goal_type::_goal_type &, typename ActionSpec::_action_result_type::_result_type &result)> service_cb)
hardware_interface::RobotHW
Diffbot::read
void read()
Definition: diffbot.h:85
hardware_interface::JointStateHandle
Diffbot
Definition: diffbot.h:51
Diffbot::running_
bool running_
Definition: diffbot.h:138
Diffbot::pos_
double pos_[NUM_JOINTS]
Definition: diffbot.h:135
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
ResourceManager< JointStateHandle >::registerHandle
void registerHandle(const JointStateHandle &handle)
Diffbot::stop_callback
bool stop_callback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: diffbot.h:125
Diffbot::start_callback
bool start_callback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: diffbot.h:119
Diffbot::getPeriod
ros::Duration getPeriod() const
Definition: diffbot.h:83
joint_state_interface.h
hardware_interface::JointHandle
ros::Time
Diffbot::vel_
double vel_[NUM_JOINTS]
Definition: diffbot.h:136
Diffbot::Diffbot
Diffbot()
Definition: diffbot.h:54
robot_hw.h
Diffbot::start_srv_
ros::ServiceServer start_srv_
Definition: diffbot.h:141
Diffbot::stop_srv_
ros::ServiceServer stop_srv_
Definition: diffbot.h:142
Diffbot::eff_
double eff_[NUM_JOINTS]
Definition: diffbot.h:137
DurationBase< Duration >::toSec
double toSec() const
ros::Duration
ros::NodeHandle
Diffbot::cmd_
double cmd_[NUM_JOINTS]
Definition: diffbot.h:134
ros::Time::now
static Time now()


diff_drive_controller
Author(s): Bence Magyar
autogenerated on Fri May 24 2024 02:41:05