Skip to content

Commit

Permalink
Use own implementation of stod (#428) (#446)
Browse files Browse the repository at this point in the history
(cherry picked from commit c9742eb)

Co-authored-by: Christoph Fröhlich <christophfroehlich@users.noreply.github.com>
  • Loading branch information
mergify[bot] and christophfroehlich committed Feb 15, 2024
1 parent 8defca7 commit 5496b18
Show file tree
Hide file tree
Showing 4 changed files with 19 additions and 9 deletions.
7 changes: 5 additions & 2 deletions example_14/hardware/rrbot_actuator_without_feedback.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
#include <vector>

#include "hardware_interface/actuator_interface.hpp"
#include "hardware_interface/lexical_casts.hpp"
#include "hardware_interface/types/hardware_interface_type_values.hpp"
#include "rclcpp/rclcpp.hpp"

Expand All @@ -41,8 +42,10 @@ hardware_interface::CallbackReturn RRBotActuatorWithoutFeedback::on_init(
return hardware_interface::CallbackReturn::ERROR;
}
// START: This part here is for exemplary purposes - Please do not copy to your production code
hw_start_sec_ = std::stod(info_.hardware_parameters["example_param_hw_start_duration_sec"]);
hw_stop_sec_ = std::stod(info_.hardware_parameters["example_param_hw_stop_duration_sec"]);
hw_start_sec_ =
hardware_interface::stod(info_.hardware_parameters["example_param_hw_start_duration_sec"]);
hw_stop_sec_ =
hardware_interface::stod(info_.hardware_parameters["example_param_hw_stop_duration_sec"]);
socket_port_ = std::stoi(info_.hardware_parameters["example_param_socket_port"]);
// END: This part here is for exemplary purposes - Please do not copy to your production code

Expand Down
11 changes: 7 additions & 4 deletions example_14/hardware/rrbot_sensor_for_position_feedback.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
#include <thread>
#include <vector>

#include "hardware_interface/lexical_casts.hpp"
#include "hardware_interface/sensor_interface.hpp"
#include "hardware_interface/types/hardware_interface_type_values.hpp"
#include "rclcpp/rclcpp.hpp"
Expand All @@ -43,9 +44,11 @@ hardware_interface::CallbackReturn RRBotSensorPositionFeedback::on_init(
return hardware_interface::CallbackReturn::ERROR;
}
// START: This part here is for exemplary purposes - Please do not copy to your production code
hw_start_sec_ = std::stod(info_.hardware_parameters["example_param_hw_start_duration_sec"]);
hw_stop_sec_ = std::stod(info_.hardware_parameters["example_param_hw_stop_duration_sec"]);
hw_slowdown_ = std::stod(info_.hardware_parameters["example_param_hw_slowdown"]);
hw_start_sec_ =
hardware_interface::stod(info_.hardware_parameters["example_param_hw_start_duration_sec"]);
hw_stop_sec_ =
hardware_interface::stod(info_.hardware_parameters["example_param_hw_stop_duration_sec"]);
hw_slowdown_ = hardware_interface::stod(info_.hardware_parameters["example_param_hw_slowdown"]);
socket_port_ = std::stoi(info_.hardware_parameters["example_param_socket_port"]);
// END: This part here is for exemplary purposes - Please do not copy to your production code

Expand Down Expand Up @@ -151,7 +154,7 @@ hardware_interface::CallbackReturn RRBotSensorPositionFeedback::on_init(
rclcpp::get_logger("RRBotSensorPositionFeedback"),
"Read form buffer sockets data: '%s'", buffer);

rt_incomming_data_ptr_.writeFromNonRT(std::stod(buffer));
rt_incomming_data_ptr_.writeFromNonRT(hardware_interface::stod(buffer));
}
else
{
Expand Down
7 changes: 5 additions & 2 deletions example_2/hardware/diffbot_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include <memory>
#include <vector>

#include "hardware_interface/lexical_casts.hpp"
#include "hardware_interface/types/hardware_interface_type_values.hpp"
#include "rclcpp/rclcpp.hpp"

Expand All @@ -37,8 +38,10 @@ hardware_interface::CallbackReturn DiffBotSystemHardware::on_init(
}

// BEGIN: This part here is for exemplary purposes - Please do not copy to your production code
hw_start_sec_ = std::stod(info_.hardware_parameters["example_param_hw_start_duration_sec"]);
hw_stop_sec_ = std::stod(info_.hardware_parameters["example_param_hw_stop_duration_sec"]);
hw_start_sec_ =
hardware_interface::stod(info_.hardware_parameters["example_param_hw_start_duration_sec"]);
hw_stop_sec_ =
hardware_interface::stod(info_.hardware_parameters["example_param_hw_stop_duration_sec"]);
// END: This part here is for exemplary purposes - Please do not copy to your production code
hw_positions_.resize(info_.joints.size(), std::numeric_limits<double>::quiet_NaN());
hw_velocities_.resize(info_.joints.size(), std::numeric_limits<double>::quiet_NaN());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include <sstream>
#include <vector>

#include "hardware_interface/lexical_casts.hpp"
#include "hardware_interface/types/hardware_interface_type_values.hpp"
#include "rclcpp/clock.hpp"
#include "rclcpp/logging.hpp"
Expand Down Expand Up @@ -51,7 +52,7 @@ hardware_interface::CallbackReturn RRBotTransmissionsSystemPositionOnlyHardware:
return hardware_interface::CallbackReturn::ERROR;
}

actuator_slowdown_ = std::stod(info_.hardware_parameters["actuator_slowdown"]);
actuator_slowdown_ = hardware_interface::stod(info_.hardware_parameters["actuator_slowdown"]);

const auto num_joints = std::accumulate(
info_.transmissions.begin(), info_.transmissions.end(), 0ul,
Expand Down

0 comments on commit 5496b18

Please sign in to comment.