Skip to content

Commit 6c5ecef

Browse files
committed
Suggestions and fixes for humble CI. write method return value handling.
1 parent 64f6b67 commit 6c5ecef

File tree

3 files changed

+8
-8
lines changed

3 files changed

+8
-8
lines changed

ign_ros2_control/include/ign_ros2_control/ign_system.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,12 +22,12 @@
2222
#include <vector>
2323

2424
#include "ign_ros2_control/ign_system_interface.hpp"
25-
#include "ign_ros2_control_parameters.hpp"
2625

2726
#include "rclcpp/executors/single_threaded_executor.hpp"
2827
#include "rclcpp_lifecycle/state.hpp"
2928
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
3029

30+
#include "ign_ros2_control_parameters.hpp"
3131

3232
namespace ign_ros2_control
3333
{

ign_ros2_control/src/MimicJointSystem.cc

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -371,6 +371,9 @@ void MimicJointSystem::PreUpdate(
371371
return;
372372
}
373373

374+
// If the mode is not ABS, default mode is PID
375+
// (e.g.) MimicJointSystemPrivate::OperationMode::PID
376+
374377
// Update force command.
375378
double force = this->dataPtr->posPid.Update(error, _info.dt);
376379

@@ -391,14 +394,12 @@ void MimicJointSystem::Update(
391394
const ignition::gazebo::UpdateInfo & /*_info*/,
392395
ignition::gazebo::EntityComponentManager & /*_ecm*/)
393396
{
394-
// ignmsg << "MimicJointSystem::Update" << std::endl;
395397
}
396398

397399
void MimicJointSystem::PostUpdate(
398400
const ignition::gazebo::UpdateInfo & /*_info*/,
399401
const ignition::gazebo::EntityComponentManager & /*_ecm*/)
400402
{
401-
// ignmsg << "MimicJointSystem::PostUpdate" << std::endl;
402403
}
403404

404405
//! [registerMimicJointSystem]

ign_ros2_control/src/ign_system.cpp

Lines changed: 4 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@
4343
#include <ignition/gazebo/components/Sensor.hh>
4444

4545
// pid_pos stuff
46-
#include <gz/math/PID.hh>
46+
#include <ignition/math/PID.hh>
4747

4848
#include <ignition/transport/Node.hh>
4949

@@ -79,10 +79,10 @@ struct jointData
7979
ignition::gazebo::Entity sim_joint;
8080

8181
/// \brief PID for position control
82-
gz::math::PID pid_pos;
82+
ignition::math::PID pid_pos;
8383

8484
/// \brief PID for velocity control
85-
gz::math::PID pid_vel;
85+
ignition::math::PID pid_vel;
8686

8787
/// \brief Control method defined in the URDF for each joint.
8888
ign_ros2_control::IgnitionSystemInterface::ControlMethod joint_control_method;
@@ -1098,9 +1098,8 @@ hardware_interface::return_type IgnitionSystem::write(
10981098
}
10991099
}
11001100
}
1101-
1102-
return hardware_interface::return_type::OK;
11031101
}
1102+
return hardware_interface::return_type::OK;
11041103
}
11051104

11061105
} // namespace ign_ros2_control

0 commit comments

Comments
 (0)