Skip to content

Commit

Permalink
Revert "Cpp fixes"
Browse files Browse the repository at this point in the history
This reverts commit c3a497c.
  • Loading branch information
ad-daniel committed Jan 17, 2023
1 parent c689352 commit 8462d81
Show file tree
Hide file tree
Showing 5 changed files with 2 additions and 7 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/tests_sources.yml
Original file line number Diff line number Diff line change
Expand Up @@ -42,4 +42,4 @@ jobs:
run: |
${{ matrix.DEPENDENCIES_INSTALLATION }}
pip install -r tests/sources/requirements.txt
python3 -m unittest discover -s tests/sources/
python3 -m unittest discover -s tests/sources/
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,6 @@
namespace webots_ros2_control {
class Ros2Control : public webots_ros2_driver::PluginInterface {
public:
Ros2Control();
void step() override;
void init(webots_ros2_driver::WebotsNode *node, std::unordered_map<std::string, std::string> &parameters) override;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,6 @@ namespace webots_ros2_control {

class Ros2ControlSystem : public Ros2ControlSystemInterface {
public:
Ros2ControlSystem();
void init(webots_ros2_driver::WebotsNode *node, const hardware_interface::HardwareInfo &info) override;

#if FOXY
Expand Down
4 changes: 1 addition & 3 deletions webots_ros2_control/src/Ros2Control.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,16 +34,14 @@ const double CONTROLLER_MANAGER_ALLOWED_SAMPLE_ERROR_MS = 1.0;

namespace webots_ros2_control {

Ros2Control::Ros2Control() { mNode = NULL; }

void Ros2Control::step() {
const int nowMs = wb_robot_get_time() * 1000.0;
const int periodMs = nowMs - mLastControlUpdateMs;
const rclcpp::Duration dt = rclcpp::Duration::from_seconds(mControlPeriodMs / 1000.0);
if (periodMs >= mControlPeriodMs) {
#if FOXY
mControllerManager->read();
#else
const rclcpp::Duration dt = rclcpp::Duration::from_seconds(mControlPeriodMs / 1000.0);
mControllerManager->read(mNode->get_clock()->now(), dt);
#endif

Expand Down
1 change: 0 additions & 1 deletion webots_ros2_control/src/Ros2ControlSystem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,6 @@
#include <webots/robot.h>

namespace webots_ros2_control {
Ros2ControlSystem::Ros2ControlSystem() { mNode = NULL; }
void Ros2ControlSystem::init(webots_ros2_driver::WebotsNode *node, const hardware_interface::HardwareInfo &info) {
mNode = node;
for (hardware_interface::ComponentInfo component : info.joints) {
Expand Down

0 comments on commit 8462d81

Please sign in to comment.