Fawkes API  Fawkes Development Version
gazsim_robotino_thread.cpp
1 /***************************************************************************
2  * gazsim_robotino_thread.cpp - Thread simulate the Robotino in Gazebo by sending needed informations to the Robotino-plugin in Gazebo and recieving sensordata from Gazebo
3  *
4  * Created: Fr 3. Mai 21:27:06 CEST 2013
5  * Copyright 2013 Frederik Zwilling
6  ****************************************************************************/
7 
8 /* This program is free software; you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation; either version 2 of the License, or
11  * (at your option) any later version.
12  *
13  * This program is distributed in the hope that it will be useful,
14  * but WITHOUT ANY WARRANTY; without even the implied warranty of
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  * GNU Library General Public License for more details.
17  *
18  * Read the full text in the LICENSE.GPL file in the doc directory.
19  */
20 
21 #include "gazsim_robotino_thread.h"
22 
23 #include <aspect/logging.h>
24 #include <core/threading/mutex_locker.h>
25 #include <interfaces/IMUInterface.h>
26 #include <interfaces/MotorInterface.h>
27 #include <interfaces/RobotinoSensorInterface.h>
28 #include <interfaces/SwitchInterface.h>
29 #include <tf/transform_publisher.h>
30 #include <tf/types.h>
31 #include <utils/math/angle.h>
32 #include <utils/time/clock.h>
33 
34 #include <cstdio>
35 #include <gazebo/msgs/msgs.hh>
36 #include <gazebo/transport/Node.hh>
37 #include <gazebo/transport/transport.hh>
38 #include <list>
39 
40 using namespace fawkes;
41 using namespace gazebo;
42 
43 /** @class RobotinoSimThread "gazsim_robotino_thread.h"
44  * Thread simulate the Robotino in Gazebo
45  * by sending needed informations to the Robotino-plugin in Gazebo
46  * and recieving sensordata from Gazebo
47  * @author Frederik Zwilling
48  */
49 
50 /** Constructor. */
52 : Thread("RobotinoSimThread", Thread::OPMODE_WAITFORWAKEUP),
53  BlockedTimingAspect(BlockedTimingAspect::WAKEUP_HOOK_WORLDSTATE), //sonsor and act here
54  TransformAspect(TransformAspect::DEFER_PUBLISHER)
55 {
56 }
57 
58 void
60 {
61  //get a connection to gazebo (copied from gazeboscene)
62  logger->log_debug(name(), "Creating Gazebo publishers");
63 
64  //read config values
65  cfg_frame_odom_ = config->get_string("/frames/odom");
66  cfg_frame_base_ = config->get_string("/frames/base");
67  cfg_frame_imu_ = config->get_string("/gazsim/robotino/imu/frame");
68  slippery_wheels_enabled_ = config->get_bool("gazsim/robotino/motor/slippery-wheels-enabled");
69  slippery_wheels_threshold_ = config->get_float("gazsim/robotino/motor/slippery-wheels-threshold");
70  moving_speed_factor_ = config->get_float("gazsim/robotino/motor/moving-speed-factor");
71  rotation_speed_factor_ = config->get_float("gazsim/robotino/motor/rotation-speed-factor");
72  gripper_laser_threshold_ = config->get_float("/gazsim/robotino/gripper-laser-threshold");
73  gripper_laser_value_far_ = config->get_float("/gazsim/robotino/gripper-laser-value-far");
74  gripper_laser_value_near_ = config->get_float("/gazsim/robotino/gripper-laser-value-near");
75  have_gripper_sensors_ = config->exists("/hardware/robotino/sensors/right_ir_id")
76  && config->exists("/hardware/robotino/sensors/left_ir_id");
77  if (have_gripper_sensors_) {
78  gripper_laser_right_pos_ = config->get_int("/hardware/robotino/sensors/right_ir_id");
79  gripper_laser_left_pos_ = config->get_int("/hardware/robotino/sensors/left_ir_id");
80  }
81  gyro_buffer_size_ = config->get_int("/gazsim/robotino/gyro-buffer-size");
82  gyro_delay_ = config->get_float("/gazsim/robotino/gyro-delay");
83  infrared_sensor_index_ = config->get_int("/gazsim/robotino/infrared-sensor-index");
84 
85  tf_enable_publisher(cfg_frame_base_.c_str());
86 
87  //Open interfaces
88  motor_if_ = blackboard->open_for_writing<MotorInterface>("Robotino");
89  switch_if_ = blackboard->open_for_writing<fawkes::SwitchInterface>("Robotino Motor");
90  sens_if_ = blackboard->open_for_writing<RobotinoSensorInterface>("Robotino");
91  imu_if_ = blackboard->open_for_writing<IMUInterface>("IMU Robotino");
92 
93  //Create suscribers
94  pos_sub_ = gazebonode->Subscribe(config->get_string("/gazsim/topics/gps"),
95  &RobotinoSimThread::on_pos_msg,
96  this);
97  gyro_sub_ = gazebonode->Subscribe(config->get_string("/gazsim/topics/gyro"),
98  &RobotinoSimThread::on_gyro_msg,
99  this);
100  infrared_puck_sensor_sub_ =
101  gazebonode->Subscribe(config->get_string("/gazsim/topics/infrared-puck-sensor"),
102  &RobotinoSimThread::on_infrared_puck_sensor_msg,
103  this);
104  if (have_gripper_sensors_) {
105  gripper_laser_left_sensor_sub_ =
106  gazebonode->Subscribe(config->get_string("/gazsim/topics/gripper-laser-left"),
107  &RobotinoSimThread::on_gripper_laser_left_sensor_msg,
108  this);
109  gripper_laser_right_sensor_sub_ =
110  gazebonode->Subscribe(config->get_string("/gazsim/topics/gripper-laser-right"),
111  &RobotinoSimThread::on_gripper_laser_right_sensor_msg,
112  this);
113  }
114 
115  //Create publishers
116  motor_move_pub_ =
117  gazebonode->Advertise<msgs::Vector3d>(config->get_string("/gazsim/topics/motor-move"));
118  string_pub_ = gazebonode->Advertise<msgs::Header>(config->get_string("/gazsim/topics/message"));
119 
120  //enable motor by default
121  switch_if_->set_enabled(true);
122  switch_if_->write();
123 
124  imu_if_->set_frame(cfg_frame_imu_.c_str());
125  imu_if_->set_linear_acceleration(0, -1.);
126  //imu_if_->set_angular_velocity_covariance(8, deg2rad(0.1));
127  // set as not available as we do not currently provide angular velocities.
128  imu_if_->set_angular_velocity_covariance(0, -1.);
129  imu_if_->write();
130 
131  //init motor variables
132  x_ = 0.0;
133  y_ = 0.0;
134  ori_ = 0.0;
135  vx_ = 0.0;
136  vy_ = 0.0;
137  vomega_ = 0.0;
138  des_vx_ = 0.0;
139  des_vy_ = 0.0;
140  des_vomega_ = 0.0;
141  x_offset_ = 0.0;
142  y_offset_ = 0.0;
143  ori_offset_ = 0.0;
144  path_length_ = 0.0;
145 
146  gyro_buffer_index_new_ = 0;
147  gyro_buffer_index_delayed_ = 0;
148  gyro_timestamp_buffer_ = new fawkes::Time[gyro_buffer_size_];
149  gyro_angle_buffer_ = new float[gyro_buffer_size_];
150 
151  new_data_ = false;
152 
153  if (string_pub_->HasConnections()) {
154  msgs::Header helloMessage;
155  helloMessage.set_str_id("gazsim-robotino plugin connected");
156  string_pub_->Publish(helloMessage);
157  }
158 }
159 
160 void
162 {
163  //close interfaces
164  blackboard->close(imu_if_);
165  blackboard->close(sens_if_);
166  blackboard->close(motor_if_);
167  blackboard->close(switch_if_);
168 
169  delete[] gyro_timestamp_buffer_;
170  delete[] gyro_angle_buffer_;
171 }
172 
173 void
175 {
176  //work off all messages passed to the motor_interfaces
177  process_motor_messages();
178 
179  //update interfaces
180  if (new_data_) {
181  motor_if_->set_odometry_position_x(x_);
182  motor_if_->set_odometry_position_y(y_);
183  motor_if_->set_odometry_orientation(ori_);
184  motor_if_->set_odometry_path_length(path_length_);
185  motor_if_->write();
186 
187  if (gyro_available_) {
188  //update gyro (with delay)
189  fawkes::Time now(clock);
190  while ((now - gyro_timestamp_buffer_[(gyro_buffer_index_delayed_ + 1) % gyro_buffer_size_])
191  .in_sec()
192  >= gyro_delay_
193  && gyro_buffer_index_delayed_ < gyro_buffer_index_new_) {
194  gyro_buffer_index_delayed_++;
195  }
196 
197  tf::Quaternion q =
198  tf::create_quaternion_from_yaw(gyro_angle_buffer_[gyro_buffer_index_delayed_]);
199  imu_if_->set_orientation(0, q.x());
200  imu_if_->set_orientation(1, q.y());
201  imu_if_->set_orientation(2, q.z());
202  imu_if_->set_orientation(3, q.w());
203  for (uint i = 0; i < 9u; i += 4) {
204  imu_if_->set_orientation_covariance(i, 1e-3);
205  imu_if_->set_angular_velocity_covariance(i, 1e-3);
206  imu_if_->set_linear_acceleration_covariance(i, 1e-3);
207  }
208  } else {
209  imu_if_->set_angular_velocity(0, -1.);
210  imu_if_->set_orientation(0, -1.);
211  imu_if_->set_orientation(1, 0.);
212  imu_if_->set_orientation(2, 0.);
213  imu_if_->set_orientation(3, 0.);
214  }
215  imu_if_->write();
216 
217  sens_if_->set_distance(infrared_sensor_index_, infrared_puck_sensor_dist_);
218 
219  if (have_gripper_sensors_) {
220  sens_if_->set_analog_in(gripper_laser_left_pos_, analog_in_left_);
221  sens_if_->set_analog_in(gripper_laser_right_pos_, analog_in_right_);
222  }
223  sens_if_->write();
224 
225  new_data_ = false;
226  }
227 }
228 
229 void
230 RobotinoSimThread::send_transroot(double vx, double vy, double omega)
231 {
232  msgs::Vector3d motorMove;
233  motorMove.set_x(vx_);
234  motorMove.set_y(vy_);
235  motorMove.set_z(vomega_);
236  motor_move_pub_->Publish(motorMove);
237 }
238 
239 void
240 RobotinoSimThread::process_motor_messages()
241 {
242  //check messages of the switch interface
243  while (!switch_if_->msgq_empty()) {
244  if (SwitchInterface::DisableSwitchMessage *msg = switch_if_->msgq_first_safe(msg)) {
245  switch_if_->set_enabled(false);
246  //pause movement
247  send_transroot(0, 0, 0);
248  } else if (SwitchInterface::EnableSwitchMessage *msg = switch_if_->msgq_first_safe(msg)) {
249  switch_if_->set_enabled(true);
250  //unpause movement
251  send_transroot(vx_, vy_, vomega_);
252  }
253  switch_if_->msgq_pop();
254  switch_if_->write();
255  }
256 
257  //do not do anything if the motor is disabled
258  if (!switch_if_->is_enabled()) {
259  return;
260  }
261 
262  //check messages of the motor interface
263  while (motor_move_pub_->HasConnections() && !motor_if_->msgq_empty()) {
264  if (MotorInterface::TransRotMessage *msg = motor_if_->msgq_first_safe(msg)) {
265  //send command only if changed
266  if (vel_changed(msg->vx(), vx_, 0.01) || vel_changed(msg->vy(), vy_, 0.01)
267  || vel_changed(msg->omega(), vomega_, 0.01)) {
268  vx_ = msg->vx();
269  vy_ = msg->vy();
270  vomega_ = msg->omega();
271  des_vx_ = vx_;
272  des_vy_ = vy_;
273  des_vomega_ = vomega_;
274 
275  //send message to gazebo (apply movement_factor to compensate friction)
276  send_transroot(vx_ * moving_speed_factor_,
277  vy_ * moving_speed_factor_,
278  vomega_ * rotation_speed_factor_);
279 
280  //update interface
281  motor_if_->set_vx(vx_);
282  motor_if_->set_vy(vy_);
283  motor_if_->set_omega(vomega_);
284  motor_if_->set_des_vx(des_vx_);
285  motor_if_->set_des_vy(des_vy_);
286  motor_if_->set_des_omega(des_vomega_);
287  //update interface
288  motor_if_->write();
289  }
290  } else if (motor_if_->msgq_first_is<MotorInterface::ResetOdometryMessage>()) {
291  x_offset_ += x_;
292  y_offset_ += y_;
293  ori_offset_ += ori_;
294  x_ = 0.0;
295  y_ = 0.0;
296  ori_ = 0.0;
297  last_vel_set_time_ = clock->now();
298  }
299  motor_if_->msgq_pop();
300  }
301 }
302 
303 bool
304 RobotinoSimThread::vel_changed(float before, float after, float relativeThreashold)
305 {
306  return (before == 0.0 || after == 0.0 || fabs((before - after) / before) > relativeThreashold);
307 }
308 
309 //Handler Methods:
310 void
311 RobotinoSimThread::on_pos_msg(ConstPosePtr &msg)
312 {
313  //logger_->log_debug(name_, "Got Position MSG from gazebo with ori: %f", msg->z());
314 
315  MutexLocker lock(loop_mutex);
316 
317  //read out values + substract offset
318  float new_x = msg->position().x() - x_offset_;
319  float new_y = msg->position().y() - y_offset_;
320  //calculate ori from quaternion
321  float new_ori = tf::get_yaw(tf::Quaternion(msg->orientation().x(),
322  msg->orientation().y(),
323  msg->orientation().z(),
324  msg->orientation().w()));
325  new_ori -= ori_offset_;
326 
327  //estimate path-length
328  float length_driven = sqrt((new_x - x_) * (new_x - x_) + (new_y - y_) * (new_y - y_));
329 
330  if (slippery_wheels_enabled_) {
331  //simulate slipping wheels when driving against an obstacle
332  fawkes::Time new_time = clock->now();
333  double duration = new_time.in_sec() - last_pos_time_.in_sec();
334  //calculate duration since the velocity was last set to filter slipping while accelerating
335  double velocity_set_duration = new_time.in_sec() - last_vel_set_time_.in_sec();
336 
337  last_pos_time_ = new_time;
338 
339  double total_speed = sqrt(vx_ * vx_ + vy_ * vy_);
340  if (length_driven < total_speed * duration * slippery_wheels_threshold_
341  && velocity_set_duration > duration) {
342  double speed_abs_x = vx_ * cos(ori_) - vy_ * sin(ori_);
343  double speed_abs_y = vx_ * sin(ori_) + vy_ * cos(ori_);
344  double slipped_x = speed_abs_x * duration * slippery_wheels_threshold_;
345  double slipped_y = speed_abs_y * duration * slippery_wheels_threshold_;
346  //logger_->log_debug(name_, "Wheels are slipping (%f, %f)", slipped_x, slipped_y);
347  new_x = x_ + slipped_x;
348  new_y = y_ + slipped_y;
349  //update the offset (otherwise the slippery error would be corrected in the next iteration)
350  x_offset_ -= slipped_x;
351  y_offset_ -= slipped_y;
352 
353  length_driven = sqrt((new_x - x_) * (new_x - x_) + (new_y - y_) * (new_y - y_));
354  }
355  }
356 
357  //update stored values
358  x_ = new_x;
359  y_ = new_y;
360  ori_ = new_ori;
361  path_length_ += length_driven;
362  new_data_ = true;
363 
364  //publish transform (otherwise the transform can not convert /base_link to /odom)
365  fawkes::Time now(clock);
366  tf::Transform t(tf::Quaternion(tf::Vector3(0, 0, 1), ori_), tf::Vector3(x_, y_, 0.0));
367 
368  tf_publisher->send_transform(t, now, cfg_frame_odom_, cfg_frame_base_);
369 }
370 void
371 RobotinoSimThread::on_gyro_msg(ConstVector3dPtr &msg)
372 {
373  MutexLocker lock(loop_mutex);
374  gyro_buffer_index_new_ = (gyro_buffer_index_new_ + 1) % gyro_buffer_size_;
375  gyro_angle_buffer_[gyro_buffer_index_new_] = msg->z();
376  gyro_timestamp_buffer_[gyro_buffer_index_new_] = clock->now();
377  gyro_available_ = true;
378  new_data_ = true;
379 }
380 void
381 RobotinoSimThread::on_infrared_puck_sensor_msg(ConstLaserScanStampedPtr &msg)
382 {
383  MutexLocker lock(loop_mutex);
384  //make sure that the config values for fetch_puck are set right
385  infrared_puck_sensor_dist_ = msg->scan().ranges(0);
386  new_data_ = true;
387 }
388 void
389 RobotinoSimThread::on_gripper_laser_right_sensor_msg(ConstFloatPtr &msg)
390 {
391  MutexLocker lock(loop_mutex);
392 
393  if (msg->value() < gripper_laser_threshold_) {
394  analog_in_right_ = gripper_laser_value_near_;
395  } else {
396  analog_in_right_ = gripper_laser_value_far_;
397  }
398  new_data_ = true;
399 }
400 void
401 RobotinoSimThread::on_gripper_laser_left_sensor_msg(ConstFloatPtr &msg)
402 {
403  MutexLocker lock(loop_mutex);
404 
405  if (msg->value() < gripper_laser_threshold_) {
406  analog_in_left_ = gripper_laser_value_near_;
407  } else {
408  analog_in_left_ = gripper_laser_value_far_;
409  }
410  new_data_ = true;
411 }
fawkes::TransformAspect::tf_enable_publisher
void tf_enable_publisher(const char *frame_id=0)
Late enabling of publisher.
Definition: tf.cpp:151
fawkes::IMUInterface::set_orientation_covariance
void set_orientation_covariance(unsigned int index, const double new_orientation_covariance)
Set orientation_covariance value at given index.
Definition: IMUInterface.cpp:259
fawkes::Interface::msgq_first_is
bool msgq_first_is()
Check if first message has desired type.
Definition: interface.h:314
fawkes::Interface::msgq_pop
void msgq_pop()
Erase first message from queue.
Definition: interface.cpp:1184
fawkes::Interface::msgq_empty
bool msgq_empty()
Check if queue is empty.
Definition: interface.cpp:1031
fawkes::IMUInterface::set_angular_velocity_covariance
void set_angular_velocity_covariance(unsigned int index, const double new_angular_velocity_covariance)
Set angular_velocity_covariance value at given index.
Definition: IMUInterface.cpp:395
fawkes::SwitchInterface
Definition: SwitchInterface.h:39
fawkes::IMUInterface
Definition: IMUInterface.h:39
fawkes::MotorInterface::set_vx
void set_vx(const float new_vx)
Set vx value.
Definition: MotorInterface.cpp:457
fawkes::MotorInterface::TransRotMessage
Definition: MotorInterface.h:366
fawkes::Interface::msgq_first_safe
MessageType * msgq_first_safe(MessageType *&msg)
Get first message casted to the desired type without exceptions.
Definition: interface.h:303
fawkes::Configuration::get_bool
virtual bool get_bool(const char *path)=0
RobotinoSimThread::init
virtual void init()
Initialize the thread.
Definition: gazsim_robotino_thread.cpp:59
fawkes::MutexLocker
Definition: mutex_locker.h:39
fawkes::RobotinoSensorInterface::set_analog_in
void set_analog_in(unsigned int index, const float new_analog_in)
Set analog_in value at given index.
Definition: RobotinoSensorInterface.cpp:521
fawkes::GazeboAspect::gazebonode
gazebo::transport::NodePtr gazebonode
Gazebo Node for communication with a robot.
Definition: gazebo.h:52
fawkes::BlockedTimingAspect
Definition: blocked_timing.h:56
fawkes::SwitchInterface::DisableSwitchMessage
Definition: SwitchInterface.h:147
fawkes::MotorInterface
Definition: MotorInterface.h:39
fawkes::Thread::name
const char * name() const
Definition: thread.h:100
fawkes::ClockAspect::clock
Clock * clock
Definition: clock.h:56
fawkes::MotorInterface::set_des_omega
void set_des_omega(const float new_des_omega)
Set des_omega value.
Definition: MotorInterface.cpp:632
fawkes::Configuration::get_int
virtual int get_int(const char *path)=0
RobotinoSimThread::RobotinoSimThread
RobotinoSimThread()
Constructor.
Definition: gazsim_robotino_thread.cpp:51
fawkes::SwitchInterface::EnableSwitchMessage
Definition: SwitchInterface.h:127
fawkes::LoggingAspect::logger
Logger * logger
Definition: logging.h:53
fawkes::MotorInterface::set_vy
void set_vy(const float new_vy)
Set vy value.
Definition: MotorInterface.cpp:492
fawkes::MotorInterface::set_odometry_position_x
void set_odometry_position_x(const float new_odometry_position_x)
Set odometry_position_x value.
Definition: MotorInterface.cpp:352
fawkes::BlackBoard::close
virtual void close(Interface *interface)=0
fawkes::MotorInterface::ResetOdometryMessage
Definition: MotorInterface.h:189
fawkes::SwitchInterface::set_enabled
void set_enabled(const bool new_enabled)
Set enabled value.
Definition: SwitchInterface.cpp:111
fawkes::Clock::now
Time now() const
Get the current time.
Definition: clock.cpp:249
fawkes
fawkes::MotorInterface::set_des_vy
void set_des_vy(const float new_des_vy)
Set des_vy value.
Definition: MotorInterface.cpp:597
fawkes::tf::TransformPublisher::send_transform
virtual void send_transform(const StampedTransform &transform, const bool is_static=false)
Publish transform.
Definition: transform_publisher.cpp:125
fawkes::RobotinoSensorInterface
Definition: RobotinoSensorInterface.h:39
fawkes::TransformAspect
Definition: tf.h:43
fawkes::RobotinoSensorInterface::set_distance
void set_distance(unsigned int index, const float new_distance)
Set distance value at given index.
Definition: RobotinoSensorInterface.cpp:341
fawkes::IMUInterface::set_orientation
void set_orientation(unsigned int index, const float new_orientation)
Set orientation value at given index.
Definition: IMUInterface.cpp:191
fawkes::ConfigurableAspect::config
Configuration * config
Definition: configurable.h:53
RobotinoSimThread::finalize
virtual void finalize()
Finalize the thread.
Definition: gazsim_robotino_thread.cpp:161
fawkes::MotorInterface::set_odometry_position_y
void set_odometry_position_y(const float new_odometry_position_y)
Set odometry_position_y value.
Definition: MotorInterface.cpp:387
fawkes::Time
Definition: time.h:98
fawkes::MotorInterface::set_des_vx
void set_des_vx(const float new_des_vx)
Set des_vx value.
Definition: MotorInterface.cpp:562
fawkes::Configuration::get_float
virtual float get_float(const char *path)=0
fawkes::Thread
Definition: thread.h:45
fawkes::MotorInterface::set_odometry_orientation
void set_odometry_orientation(const float new_odometry_orientation)
Set odometry_orientation value.
Definition: MotorInterface.cpp:422
fawkes::TransformAspect::tf_publisher
tf::TransformPublisher * tf_publisher
Definition: tf.h:73
fawkes::BlackBoardAspect::blackboard
BlackBoard * blackboard
Definition: blackboard.h:49
fawkes::Configuration::get_string
virtual std::string get_string(const char *path)=0
fawkes::MotorInterface::set_omega
void set_omega(const float new_omega)
Set omega value.
Definition: MotorInterface.cpp:527
fawkes::SwitchInterface::is_enabled
bool is_enabled() const
Get enabled value.
Definition: SwitchInterface.cpp:89
fawkes::Thread::loop_mutex
Mutex * loop_mutex
Definition: thread.h:152
fawkes::IMUInterface::set_linear_acceleration_covariance
void set_linear_acceleration_covariance(unsigned int index, const double new_linear_acceleration_covariance)
Set linear_acceleration_covariance value at given index.
Definition: IMUInterface.cpp:531
fawkes::Configuration::exists
virtual bool exists(const char *path)=0
fawkes::Logger::log_debug
virtual void log_debug(const char *component, const char *format,...)=0
fawkes::Interface::write
void write()
Write from local copy into BlackBoard memory.
Definition: interface.cpp:499
fawkes::BlackBoard::open_for_writing
virtual Interface * open_for_writing(const char *interface_type, const char *identifier, const char *owner=NULL)=0
fawkes::Time::in_sec
double in_sec() const
Convet time to seconds.
Definition: time.cpp:226
RobotinoSimThread::loop
virtual void loop()
Code to execute in the thread.
Definition: gazsim_robotino_thread.cpp:174
fawkes::IMUInterface::set_angular_velocity
void set_angular_velocity(unsigned int index, const float new_angular_velocity)
Set angular_velocity value at given index.
Definition: IMUInterface.cpp:327
fawkes::MotorInterface::set_odometry_path_length
void set_odometry_path_length(const float new_odometry_path_length)
Set odometry_path_length value.
Definition: MotorInterface.cpp:317