diffbot_hw_interface.cpp
Go to the documentation of this file.
2 
3 // ROS parameter loading
5 
6 //#include <std_msgs/Float32.h>
7 #include <std_msgs/Int32.h>
8 #include <std_msgs/Empty.h>
9 
10 #include <iomanip>
11 
12 namespace diffbot_base
13 {
15  : name_("hardware_interface")
16  , nh_(nh)
17  {
18  // Initialization of the robot's resources (joints, sensors, actuators) and
19  // interfaces can be done here or inside init().
20  // E.g. parse the URDF for joint names & interfaces, then initialize them
21  // Check if the URDF model needs to be loaded
22  if (urdf_model == NULL)
23  loadURDF(nh, "robot_description");
24  else
25  urdf_model_ = urdf_model;
26 
27  // Load rosparams
28  ros::NodeHandle rpnh(nh_, name_);
29  std::size_t error = 0;
30  // Code API of rosparam_shortcuts:
31  // http://docs.ros.org/en/noetic/api/rosparam_shortcuts/html/namespacerosparam__shortcuts.html#aa6536fe0130903960b1de4872df68d5d
32  error += !rosparam_shortcuts::get(name_, rpnh, "joints", joint_names_);
33  error += !rosparam_shortcuts::get(name_, nh_, "mobile_base_controller/wheel_radius", wheel_radius_);
34  error += !rosparam_shortcuts::get(name_, nh_, "mobile_base_controller/linear/x/max_velocity", max_velocity_);
35  // Get additional parameters from the diffbot_base/config/base.yaml which is stored on the parameter server
36  error += !rosparam_shortcuts::get(name_, nh_, "encoder_resolution", encoder_resolution_);
37  error += !rosparam_shortcuts::get(name_, nh_, "gain", gain_);
38  error += !rosparam_shortcuts::get(name_, nh_, "trim", trim_);
39  error += !rosparam_shortcuts::get(name_, nh_, "motor_constant", motor_constant_);
40  error += !rosparam_shortcuts::get(name_, nh_, "pwm_limit", pwm_limit_);
41  error += !rosparam_shortcuts::get(name_, nh_, "debug/hardware_interface", debug_);
43 
45  //max_velocity_ = 0.2; // m/s
46  // ros_control RobotHW needs velocity in rad/s but in the config its given in m/s
48 
49 
50  ROS_INFO_STREAM("mobile_base_controller/wheel_radius: " << wheel_radius_);
51  ROS_INFO_STREAM("mobile_base_controller/linear/x/max_velocity: " << max_velocity_);
52  ROS_INFO_STREAM("encoder_resolution: " << encoder_resolution_);
53  ROS_INFO_STREAM("gain: " << gain_);
54  ROS_INFO_STREAM("trim: " << trim_);
55  ROS_INFO_STREAM("motor_constant: " << motor_constant_);
56  ROS_INFO_STREAM("pwm_limit: " << pwm_limit_);
57 
58  // Setup publisher for the motor driver
59  pub_left_motor_value_ = nh_.advertise<std_msgs::Int32>("motor_left", 10);
60  pub_right_motor_value_ = nh_.advertise<std_msgs::Int32>("motor_right", 10);
61 
62  //Setup publisher for angular wheel joint velocity commands
64 
65  // Setup publisher to reset wheel encoders (used during first launch of the hardware interface)
66  pub_reset_encoders_ = nh_.advertise<std_msgs::Empty>("reset", 10);
67  // Setup subscriber for the wheel encoders
70 
71  // Initialize the hardware interface
72  init(nh_, nh_);
73 
74  // Wait for encoder messages being published
76  }
77 
78 
80  {
81  ROS_INFO("Initializing DiffBot Hardware Interface ...");
82  num_joints_ = joint_names_.size();
83  ROS_INFO("Number of joints: %d", (int)num_joints_);
84  std::array<std::string, NUM_JOINTS> motor_names = {"left_motor", "right_motor"};
85  for (unsigned int i = 0; i < num_joints_; i++)
86  {
87  // Create a JointStateHandle for each joint and register them with the
88  // JointStateInterface.
90  &joint_positions_[i],
92  &joint_efforts_[i]);
93  joint_state_interface_.registerHandle(joint_state_handle);
94 
95  // Create a JointHandle (read and write) for each controllable joint
96  // using the read-only joint handles within the JointStateInterface and
97  // register them with the JointVelocityInterface.
98  hardware_interface::JointHandle joint_handle(joint_state_handle, &joint_velocity_commands_[i]);
100 
101  // Initialize joint states with zero values
102  joint_positions_[i] = 0.0;
103  joint_velocities_[i] = 0.0;
104  joint_efforts_[i] = 0.0; // unused with diff_drive_controller
105 
106  joint_velocity_commands_[i] = 0.0;
107 
108  // Initialize encoder_ticks_ to zero because receiving meaningful
109  // tick values from the microcontroller might take some time
110  encoder_ticks_[i] = 0.0;
113 
114  // Initialize the pid controllers for the motors using the robot namespace
115  std::string pid_namespace = "pid/" + motor_names[i];
116  ROS_INFO_STREAM("pid namespace: " << pid_namespace);
117  ros::NodeHandle nh(root_nh, pid_namespace);
118  // TODO implement builder pattern to initialize values otherwise it is hard to see which parameter is what.
119  pids_[i].init(nh, 0.8, 0.35, 0.5, 0.01, 3.5, -3.5, false, max_velocity_, -max_velocity_);
121  }
122 
123  // Register the JointStateInterface containing the read only joints
124  // with this robot's hardware_interface::RobotHW.
126 
127  // Register the JointVelocityInterface containing the read/write joints
128  // with this robot's hardware_interface::RobotHW.
130 
131  ROS_INFO("... Done Initializing DiffBot Hardware Interface");
132 
133  return true;
134  }
135 
136  void DiffBotHWInterface::read(const ros::Time& time, const ros::Duration& period)
137  {
138  //ROS_INFO_THROTTLE(1, "Read");
139  ros::Duration elapsed_time = period;
140 
141  // Read from robot hw (motor encoders)
142  // Fill joint_state_* members with read values
143  for (std::size_t i = 0; i < num_joints_; ++i)
144  {
147  joint_efforts_[i] = 0.0; // unused with diff_drive_controller
148  }
149 
150  if (debug_)
151  {
152  const int width = 10;
153  const char sep = ' ';
154  std::stringstream ss;
155  ss << std::left << std::setw(width) << std::setfill(sep) << "Read" << std::left << std::setw(width) << std::setfill(sep) << "ticks" << std::left << std::setw(width) << std::setfill(sep) << "angle" << std::left << std::setw(width) << std::setfill(sep) << "velocity" << std::endl;
156  ss << std::left << std::setw(width) << std::setfill(sep) << "j0:" << std::left << std::setw(width) << std::setfill(sep) << encoder_ticks_[0] << std::left << std::setw(width) << std::setfill(sep) << joint_positions_[0] << std::left << std::setw(width) << std::setfill(sep) << joint_velocities_[0] << std::endl;
157  ss << std::left << std::setw(width) << std::setfill(sep) << "j1:" << std::left << std::setw(width) << std::setfill(sep) << encoder_ticks_[1] << std::left << std::setw(width) << std::setfill(sep) << joint_positions_[1] << std::left << std::setw(width) << std::setfill(sep) << std::setfill(sep) << joint_velocities_[1];
158  ROS_INFO_STREAM(std::endl << ss.str());
159  //printState();
160  }
161  }
162 
163  void DiffBotHWInterface::write(const ros::Time& time, const ros::Duration& period)
164  {
165  ros::Duration elapsed_time = period;
166  // Write to robot hw
167  // joint velocity commands from ros_control's RobotHW are in rad/s
168 
169  // adjusting k by gain and trim
170  double motor_constant_right_inv = (gain_ + trim_) / motor_constant_;
171  double motor_constant_left_inv = (gain_ - trim_) / motor_constant_;
172 
173 
174  joint_velocity_commands_[0] = joint_velocity_commands_[0] * motor_constant_left_inv;
175  joint_velocity_commands_[1] = joint_velocity_commands_[1] * motor_constant_right_inv;
176 
177 
178  // Publish the desired (commanded) angular wheel joint velocities
179  diffbot_msgs::WheelsCmdStamped wheel_cmd_msg;
180  wheel_cmd_msg.header.stamp = ros::Time::now();
181  for (int i = 0; i < NUM_JOINTS; ++i)
182  {
183  wheel_cmd_msg.wheels_cmd.angular_velocities.joint.push_back(joint_velocity_commands_[i]);
184  }
185 
186  pub_wheel_cmd_velocities_.publish(wheel_cmd_msg);
187 
188  // The following code provides another velocity commands interface
189  // With it a motor driver node can directly subscribe to the desired velocities.
190 
191  // Convert the velocity command to a percentage value for the motor
192  // This maps the velocity to a percentage value which is used to apply
193  // a percentage of the highest possible battery voltage to each motor.
194  std_msgs::Int32 left_motor;
195  std_msgs::Int32 right_motor;
196 
197  double pid_outputs[NUM_JOINTS];
198  double motor_cmds[NUM_JOINTS] ;
199  pid_outputs[0] = pids_[0](joint_velocities_[0], joint_velocity_commands_[0], period);
200  pid_outputs[1] = pids_[1](joint_velocities_[1], joint_velocity_commands_[1], period);
201 
202  motor_cmds[0] = pid_outputs[0] / max_velocity_ * 100.0;
203  motor_cmds[1] = pid_outputs[1] / max_velocity_ * 100.0;
204  left_motor.data = motor_cmds[0];
205  right_motor.data = motor_cmds[1];
206 
207  // Calibrate motor commands to deal with different gear friction in the
208  // left and right motors and possible differences in the wheels.
209  // Add calibration offsets to motor output in low regions
210  // To tune these offset values command the robot to drive in a straight line and
211  // adjust if it isn't going straight.
212  // int left_offset = 10;
213  // int right_offset = 5;
214  // int threshold = 55;
215  // if (0 < left_motor.data && left_motor.data < threshold)
216  // {
217  // // the second part of the multiplication lets the offset decrease with growing motor values
218  // left_motor.data += left_offset * (threshold - left_motor.data) / threshold;
219  // }
220  // if (0 < right_motor.data && right_motor.data < threshold)
221  // {
222  // // the second part of the multiplication lets the offset decrease with growing motor values
223  // right_motor.data += right_offset * (threshold - right_motor.data) / threshold;
224  // }
225 
226  pub_left_motor_value_.publish(left_motor);
227  pub_right_motor_value_.publish(right_motor);
228 
229 
230  if (debug_)
231  {
232  const int width = 10;
233  const char sep = ' ';
234  std::stringstream ss;
235  // Header
236  ss << std::left << std::setw(width) << std::setfill(sep) << "Write"
237  << std::left << std::setw(width) << std::setfill(sep) << "velocity"
238  << std::left << std::setw(width) << std::setfill(sep) << "p_error"
239  << std::left << std::setw(width) << std::setfill(sep) << "i_error"
240  << std::left << std::setw(width) << std::setfill(sep) << "d_error"
241  << std::left << std::setw(width) << std::setfill(sep) << "pid out"
242  << std::left << std::setw(width) << std::setfill(sep) << "percent"
243  << std::endl;
244  double p_error, i_error, d_error;
245  for (int i = 0; i < NUM_JOINTS; ++i)
246  {
247  pids_[i].getCurrentPIDErrors(&p_error, &i_error, &d_error);
248 
249  // Joint i
250  std::string j = "j" + std::to_string(i) + ":";
251  ss << std::left << std::setw(width) << std::setfill(sep) << j
252  << std::left << std::setw(width) << std::setfill(sep) << joint_velocity_commands_[i]
253  << std::left << std::setw(width) << std::setfill(sep) << p_error
254  << std::left << std::setw(width) << std::setfill(sep) << i_error
255  << std::left << std::setw(width) << std::setfill(sep) << d_error
256  << std::left << std::setw(width) << std::setfill(sep) << pid_outputs[i]
257  << std::left << std::setw(width) << std::setfill(sep) << motor_cmds[i]
258  << std::endl;
259  }
260  ROS_INFO_STREAM(std::endl << ss.str());
261  }
262  }
263 
265  {
266  ROS_INFO("Get number of measured joint states publishers");
267 
269  int num_publishers = sub_measured_joint_states_.getNumPublishers();
270  ROS_INFO("Waiting for measured joint states being published...");
271  while ((num_publishers == 0) && (ros::Time::now() < start + timeout))
272  {
273  ros::Duration(0.1).sleep();
274  num_publishers = sub_measured_joint_states_.getNumPublishers();
275  }
276  if (num_publishers == 0)
277  {
278  ROS_ERROR("No measured joint states publishers. Timeout reached.");
279  }
280  else
281  {
282  ROS_INFO_STREAM("Number of measured joint states publishers: " << num_publishers);
283  }
284 
285  ROS_INFO("Publish /reset to encoders");
286  std_msgs::Empty msg;
288 
289  return (num_publishers > 0);
290  }
291 
292  void DiffBotHWInterface::loadURDF(const ros::NodeHandle &nh, std::string param_name)
293  {
294  std::string urdf_string;
295  urdf_model_ = new urdf::Model();
296 
297  // search and wait for robot_description on param server
298  while (urdf_string.empty() && ros::ok())
299  {
300  std::string search_param_name;
301  if (nh.searchParam(param_name, search_param_name))
302  {
303  ROS_INFO_STREAM_NAMED(name_, "Waiting for model URDF on the ROS param server at location: " <<
304  nh.getNamespace() << search_param_name);
305  nh.getParam(search_param_name, urdf_string);
306  }
307  else
308  {
309  ROS_INFO_STREAM_NAMED(name_, "Waiting for model URDF on the ROS param server at location: " <<
310  nh.getNamespace() << param_name);
311  nh.getParam(param_name, urdf_string);
312  }
313 
314  usleep(100000);
315  }
316 
317  if (!urdf_model_->initString(urdf_string))
318  ROS_ERROR_STREAM_NAMED(name_, "Unable to load URDF model");
319  else
320  ROS_DEBUG_STREAM_NAMED(name_, "Received URDF from param server");
321  }
322 
324  {
325  // WARNING: THIS IS NOT REALTIME SAFE
326  // FOR DEBUGGING ONLY, USE AT YOUR OWN ROBOT's RISK!
327  ROS_INFO_STREAM_THROTTLE(1, std::endl << printStateHelper());
328  }
329 
331  {
332  std::stringstream ss;
333  std::cout.precision(15);
334 
335  for (std::size_t i = 0; i < num_joints_; ++i)
336  {
337  ss << "j" << i << ": " << std::fixed << joint_positions_[i] << "\t ";
338  ss << std::fixed << joint_velocities_[i] << "\t ";
339  ss << std::fixed << joint_efforts_[i] << std::endl;
340  }
341  return ss.str();
342  }
343 
345  {
346  std::stringstream ss;
347  std::cout.precision(15);
348  ss << " position velocity effort \n";
349  for (std::size_t i = 0; i < num_joints_; ++i)
350  {
351  ss << std::fixed << joint_velocity_commands_[i] << "\t ";
352  }
353  return ss.str();
354  }
355 
356 
358  void DiffBotHWInterface::encoderTicksCallback(const diffbot_msgs::EncodersStamped::ConstPtr& msg_encoder)
359  {
361  encoder_ticks_[0] = msg_encoder->encoders.ticks[0];
362  encoder_ticks_[1] = msg_encoder->encoders.ticks[1];
363  ROS_DEBUG_STREAM_THROTTLE(1, "Left encoder ticks: " << encoder_ticks_[0]);
364  ROS_DEBUG_STREAM_THROTTLE(1, "Right encoder ticks: " << encoder_ticks_[1]);
365  }
366 
367  void DiffBotHWInterface::measuredJointStatesCallback(const sensor_msgs::JointState::ConstPtr& msg_joint_states)
368  {
370  for (std::size_t i = 0; i < num_joints_; ++i)
371  {
372  measured_joint_states_[i].angular_position_ = msg_joint_states->position[i];
373  measured_joint_states_[i].angular_velocity_ = msg_joint_states->velocity[i];
374  }
375  //ROS_DEBUG_STREAM_THROTTLE(1, "Left encoder ticks: " << encoder_ticks_[0]);
376  //ROS_DEBUG_STREAM_THROTTLE(1, "Right encoder ticks: " << encoder_ticks_[1]);
377  }
378 
379 
380  double DiffBotHWInterface::ticksToAngle(const int &ticks) const
381  {
382  // Convert number of encoder ticks to angle in radians
383  double angle = (double)ticks * (2.0*M_PI / encoder_resolution_);
384  ROS_DEBUG_STREAM_THROTTLE(1, ticks << " ticks correspond to an angle of " << angle);
385  return angle;
386  }
387 
388  double DiffBotHWInterface::normalizeAngle(double &angle) const
389  {
390  // https://stackoverflow.com/questions/11498169/dealing-with-angle-wrap-in-c-code
391  angle = fmod(angle, 2.0*M_PI);
392 
393  if (angle < 0)
394  angle += 2.0*M_PI;
395 
396  ROS_DEBUG_STREAM_THROTTLE(1, "Normalized angle: " << angle);
397  return angle;
398  }
399 
400 
401  double DiffBotHWInterface::linearToAngular(const double &distance) const
402  {
403  return distance / wheel_diameter_ * 2.0;
404  }
405 
406  double DiffBotHWInterface::angularToLinear(const double &angle) const
407  {
408  return angle * wheel_diameter_ / 2.0;
409  }
410 
411 };
diffbot_base::DiffBotHWInterface::velocity_joint_interface_
hardware_interface::VelocityJointInterface velocity_joint_interface_
Definition: diffbot_hw_interface.h:163
control_toolbox::Pid::getCurrentPIDErrors
void getCurrentPIDErrors(double *pe, double *ie, double *de)
msg
msg
diffbot_msgs::WheelsCmdStamped
Definition: WheelsCmdStamped.h:14
angle
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
diffbot_base::DiffBotHWInterface::pub_left_motor_value_
ros::Publisher pub_left_motor_value_
Definition: diffbot_hw_interface.h:208
diffbot_base::DiffBotHWInterface::pids_
PID pids_[NUM_JOINTS]
Definition: diffbot_hw_interface.h:229
ROS_DEBUG_STREAM_NAMED
#define ROS_DEBUG_STREAM_NAMED(name, args)
rosparam_shortcuts::get
bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string &param_name, bool &value)
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
hardware_interface::InterfaceManager::registerInterface
void registerInterface(T *iface)
diffbot_base::DiffBotHWInterface::read
virtual void read(const ros::Time &time, const ros::Duration &period) override
Read data from the robot hardware.
Definition: diffbot_hw_interface.cpp:136
diffbot_msgs::WheelsCmd::angular_velocities
_angular_velocities_type angular_velocities
Definition: WheelsCmd.h:17
diffbot_base::DiffBotHWInterface::write
virtual void write(const ros::Time &time, const ros::Duration &period)
Write commands to the robot hardware.
Definition: diffbot_hw_interface.cpp:163
diffbot_base::PID::init
void init(ros::NodeHandle &nh, double f, double p, double i, double d, double i_max, double i_min, bool antiwindup, double out_max, double out_min)
Initialize the.
Definition: src/pid.cpp:18
diffbot_base::DiffBotHWInterface::printState
virtual void printState()
Helper for debugging a joint's state.
Definition: diffbot_hw_interface.cpp:323
diffbot_base::PID::setOutputLimits
void setOutputLimits(double out_min, double out_max)
Set the Output Limits of the PID controller.
Definition: src/pid.cpp:87
diffbot_base::DiffBotHWInterface::encoderTicksCallback
void encoderTicksCallback(const diffbot_msgs::EncodersStamped::ConstPtr &msg_encoders)
Callback to receive the encoder ticks from Teensy MCU.
Definition: diffbot_hw_interface.cpp:358
diffbot_base::DiffBotHWInterface::joint_state_interface_
hardware_interface::JointStateInterface joint_state_interface_
Definition: diffbot_hw_interface.h:156
diffbot_base::DiffBotHWInterface::sub_measured_joint_states_
ros::Subscriber sub_measured_joint_states_
Definition: diffbot_hw_interface.h:223
diffbot_base::DiffBotHWInterface::linearToAngular
double linearToAngular(const double &distance) const
DiffBot reports travel distance in metres, need radians for ros_control RobotHW.
Definition: diffbot_hw_interface.cpp:401
urdf::Model
diffbot_base::DiffBotHWInterface::printStateHelper
std::string printStateHelper()
Definition: diffbot_hw_interface.cpp:330
diffbot_base::DiffBotHWInterface::loadURDF
virtual void loadURDF(const ros::NodeHandle &nh, std::string param_name)
Get the URDF XML from the parameter server.
Definition: diffbot_hw_interface.cpp:292
diffbot_base::DiffBotHWInterface::printCommandHelper
std::string printCommandHelper()
Helper for debugging a joint's command.
Definition: diffbot_hw_interface.cpp:344
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ok
ROSCPP_DECL bool ok()
diffbot_base::DiffBotHWInterface::sub_encoder_ticks_
ros::Subscriber sub_encoder_ticks_
Definition: diffbot_hw_interface.h:220
diffbot_base::DiffBotHWInterface::pub_right_motor_value_
ros::Publisher pub_right_motor_value_
Definition: diffbot_hw_interface.h:209
ros::Subscriber::getNumPublishers
uint32_t getNumPublishers() const
diffbot_base::DiffBotHWInterface::joint_velocity_commands_
double joint_velocity_commands_[NUM_JOINTS]
Definition: diffbot_hw_interface.h:195
diffbot_base::DiffBotHWInterface::measured_joint_states_
JointState measured_joint_states_[NUM_JOINTS]
Definition: diffbot_hw_interface.h:227
diffbot_base::DiffBotHWInterface::angularToLinear
double angularToLinear(const double &angle) const
RobotHW provides velocity command in rad/s, DiffBot needs m/s.
Definition: diffbot_hw_interface.cpp:406
diffbot_base::DiffBotHWInterface::nh_
ros::NodeHandle nh_
Definition: diffbot_hw_interface.h:151
diffbot_base::DiffBotHWInterface::encoder_resolution_
double encoder_resolution_
Definition: diffbot_hw_interface.h:176
diffbot_base::DiffBotHWInterface::init
virtual bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)
The init function is called to initialize the RobotHW from a non-realtime thread.
Definition: diffbot_hw_interface.cpp:79
diffbot_base::DiffBotHWInterface::pwm_limit_
double pwm_limit_
Definition: diffbot_hw_interface.h:182
diffbot_base::DiffBotHWInterface::DiffBotHWInterface
DiffBotHWInterface(ros::NodeHandle &nh, urdf::Model *urdf_model=NULL)
Constructor.
Definition: diffbot_hw_interface.cpp:14
ROS_INFO_STREAM_THROTTLE
#define ROS_INFO_STREAM_THROTTLE(period, args)
diffbot_base::DiffBotHWInterface::normalizeAngle
double normalizeAngle(double &angle) const
Normalize angle in the range of [0, 360)
Definition: diffbot_hw_interface.cpp:388
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
diffbot_base::JointState::angular_position_
float angular_position_
Definition: diffbot_hw_interface.h:27
ros::NodeHandle::searchParam
bool searchParam(const std::string &key, std::string &result) const
hardware_interface::JointStateHandle
rosparam_shortcuts.h
ROS_DEBUG_STREAM_THROTTLE
#define ROS_DEBUG_STREAM_THROTTLE(period, args)
nh
ros::NodeHandle nh
Definition: main.cpp:8
diffbot_hw_interface.h
diffbot_base::DiffBotHWInterface::wheel_radius_
double wheel_radius_
Definition: diffbot_hw_interface.h:170
diffbot_base::DiffBotHWInterface::trim_
double trim_
Definition: diffbot_hw_interface.h:179
diffbot_base::DiffBotHWInterface::joint_velocities_
double joint_velocities_[NUM_JOINTS]
Definition: diffbot_hw_interface.h:201
diffbot_base::DiffBotHWInterface::pub_reset_encoders_
ros::Publisher pub_reset_encoders_
Definition: diffbot_hw_interface.h:217
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
urdf::Model::initString
URDF_EXPORT bool initString(const std::string &xmlstring)
diffbot_base::DiffBotHWInterface::gain_
double gain_
Definition: diffbot_hw_interface.h:178
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
diffbot_base::DiffBotHWInterface::joint_names_
std::vector< std::string > joint_names_
Definition: diffbot_hw_interface.h:166
diffbot_base::DiffBotHWInterface::encoder_ticks_
int encoder_ticks_[NUM_JOINTS]
Definition: diffbot_hw_interface.h:226
ResourceManager< JointStateHandle >::registerHandle
void registerHandle(const JointStateHandle &handle)
diffbot_base::DiffBotHWInterface::joint_efforts_
double joint_efforts_[NUM_JOINTS]
Definition: diffbot_hw_interface.h:202
diffbot_base::DiffBotHWInterface::urdf_model_
urdf::Model * urdf_model_
Definition: diffbot_hw_interface.h:168
diffbot_base::NUM_JOINTS
const unsigned int NUM_JOINTS
Definition: diffbot_hw_interface.h:23
diffbot_base::DiffBotHWInterface::pub_wheel_cmd_velocities_
ros::Publisher pub_wheel_cmd_velocities_
Definition: diffbot_hw_interface.h:213
diffbot_base::DiffBotHWInterface::measuredJointStatesCallback
void measuredJointStatesCallback(const sensor_msgs::JointState::ConstPtr &msg_joint_states)
Callback to receive the measured joint states from Teensy MCU.
Definition: diffbot_hw_interface.cpp:367
start
ROSCPP_DECL void start()
diffbot_base
Definition: diffbot_hw_interface.h:21
diffbot_base::DiffBotHWInterface::joint_positions_
double joint_positions_[NUM_JOINTS]
Definition: diffbot_hw_interface.h:200
hardware_interface::JointHandle
diffbot_msgs::WheelsCmdStamped::header
_header_type header
Definition: WheelsCmdStamped.h:18
ros::Time
diffbot_base::JointState::angular_velocity_
float angular_velocity_
Definition: diffbot_hw_interface.h:28
diffbot_msgs::WheelsCmdStamped::wheels_cmd
_wheels_cmd_type wheels_cmd
Definition: WheelsCmdStamped.h:20
diffbot_msgs::AngularVelocities::joint
_joint_type * joint
Definition: AngularVelocities.h:18
ROS_ERROR
#define ROS_ERROR(...)
ROS_INFO_STREAM_NAMED
#define ROS_INFO_STREAM_NAMED(name, args)
diffbot_base::DiffBotHWInterface::ticksToAngle
double ticksToAngle(const int &ticks) const
Convert number of encoder ticks to angle in radians.
Definition: diffbot_hw_interface.cpp:380
diffbot_base::DiffBotHWInterface::max_velocity_
double max_velocity_
Definition: diffbot_hw_interface.h:172
ros::Duration::sleep
bool sleep() const
diffbot_base::DiffBotHWInterface::motor_constant_
double motor_constant_
Definition: diffbot_hw_interface.h:181
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
ROS_INFO
#define ROS_INFO(...)
ros::Duration
diffbot_base::DiffBotHWInterface::num_joints_
std::size_t num_joints_
Definition: diffbot_hw_interface.h:167
diffbot_base::DiffBotHWInterface::wheel_diameter_
double wheel_diameter_
Definition: diffbot_hw_interface.h:171
rosparam_shortcuts::shutdownIfError
void shutdownIfError(const std::string &parent_name, std::size_t error_count)
diffbot_base::DiffBotHWInterface::name_
std::string name_
Definition: diffbot_hw_interface.h:148
diffbot_base::DiffBotHWInterface::isReceivingMeasuredJointStates
bool isReceivingMeasuredJointStates(const ros::Duration &timeout=ros::Duration(1))
Check if measured joint states (position and velocity) are received.
Definition: diffbot_hw_interface.cpp:264
ros::NodeHandle
ros::Time::now
static Time now()
diffbot_base::DiffBotHWInterface::debug_
bool debug_
Definition: diffbot_hw_interface.h:187


diffbot_base
Author(s):
autogenerated on Thu Sep 7 2023 02:35:23