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 // ROS
31 #include <ros/ros.h>
32 #include <std_msgs/Float64.h>
33 #include <std_srvs/Empty.h>
34 
35 // ros_control
36 #include <controller_manager/controller_manager.h>
41 
42 // NaN
43 #include <limits>
44 
45 // ostringstream
46 #include <sstream>
47 
48 template <unsigned int NUM_JOINTS = 2>
50 {
51 public:
53  : running_(true)
56  {
57  // Intialize raw data
58  std::fill_n(pos_, NUM_JOINTS, 0.0);
59  std::fill_n(vel_, NUM_JOINTS, 0.0);
60  std::fill_n(eff_, NUM_JOINTS, 0.0);
61  std::fill_n(cmd_, NUM_JOINTS, 0.0);
62 
63  // Connect and register the joint state and velocity interface
64  for (unsigned int i = 0; i < NUM_JOINTS; ++i)
65  {
66  std::ostringstream os;
67  os << "wheel_" << i << "_joint";
68 
69  hardware_interface::JointStateHandle state_handle(os.str(), &pos_[i], &vel_[i], &eff_[i]);
71 
74  }
75 
78  }
79 
80  ros::Time getTime() const {return ros::Time::now();}
81  ros::Duration getPeriod() const {return ros::Duration(0.01);}
82 
83  void read()
84  {
85  std::ostringstream os;
86  for (unsigned int i = 0; i < NUM_JOINTS - 1; ++i)
87  {
88  os << cmd_[i] << ", ";
89  }
90  os << cmd_[NUM_JOINTS - 1];
91 
92  ROS_INFO_STREAM("Commands for joints: " << os.str());
93  }
94 
95  void write()
96  {
97  if (running_)
98  {
99  for (unsigned int i = 0; i < NUM_JOINTS; ++i)
100  {
101  // Note that pos_[i] will be NaN for one more cycle after we start(),
102  // but that is consistent with the knowledge we have about the state
103  // of the robot.
104  pos_[i] += vel_[i]*getPeriod().toSec(); // update position
105  vel_[i] = cmd_[i]; // might add smoothing here later
106  }
107  }
108  else
109  {
110  std::fill_n(pos_, NUM_JOINTS, std::numeric_limits<double>::quiet_NaN());
111  std::fill_n(vel_, NUM_JOINTS, std::numeric_limits<double>::quiet_NaN());
112  }
113  }
114 
115  bool start_callback(std_srvs::Empty::Request& /*req*/, std_srvs::Empty::Response& /*res*/)
116  {
117  running_ = true;
118  return true;
119  }
120 
121  bool stop_callback(std_srvs::Empty::Request& /*req*/, std_srvs::Empty::Response& /*res*/)
122  {
123  running_ = false;
124  return true;
125  }
126 
127 private:
130  double cmd_[NUM_JOINTS];
131  double pos_[NUM_JOINTS];
132  double vel_[NUM_JOINTS];
133  double eff_[NUM_JOINTS];
134  bool running_;
135 
139 };
hardware_interface::JointStateInterface jnt_state_interface_
Definition: diffbot.h:128
bool start_callback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: diffbot.h:115
ros::ServiceServer stop_srv_
Definition: diffbot.h:138
ros::Duration getPeriod() const
Definition: diffbot.h:81
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)
double vel_[NUM_JOINTS]
Definition: diffbot.h:132
ros::Time getTime() const
Definition: diffbot.h:80
hardware_interface::VelocityJointInterface jnt_vel_interface_
Definition: diffbot.h:129
double cmd_[NUM_JOINTS]
Definition: diffbot.h:130
ros::NodeHandle nh_
Definition: diffbot.h:136
ros::ServiceServer start_srv_
Definition: diffbot.h:137
Diffbot()
Definition: diffbot.h:52
void registerHandle(const JointStateHandle &handle)
JointStateHandle getHandle(const std::string &name)
#define ROS_INFO_STREAM(args)
bool stop_callback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: diffbot.h:121
void write()
Definition: diffbot.h:95
static Time now()
bool running_
Definition: diffbot.h:134
double pos_[NUM_JOINTS]
Definition: diffbot.h:131
double eff_[NUM_JOINTS]
Definition: diffbot.h:133
void read()
Definition: diffbot.h:83


diff_drive_controller
Author(s): Bence Magyar
autogenerated on Thu Apr 11 2019 03:08:07