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


diff_drive_controller
Author(s): Bence Magyar
autogenerated on Fri Feb 3 2023 03:19:01