Skip to content
This repository was archived by the owner on Oct 17, 2025. It is now read-only.

Commit c613239

Browse files
committed
Fixed velocity example
Signed-off-by: ahcorde <[email protected]>
1 parent 4039a06 commit c613239

File tree

3 files changed

+2
-12
lines changed

3 files changed

+2
-12
lines changed

gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -83,9 +83,6 @@ class GazeboSystem : public GazeboSystemInterface
8383
/// \brief last time the write method was called.
8484
rclcpp::Time last_update_sim_time_ros_;
8585

86-
/// \brief it is ODE physics engine?
87-
bool usingODE;
88-
8986
/// \brief vector with the joint's names.
9087
std::vector<std::string> joint_names_;
9188

gazebo_ros2_control/src/gazebo_system.cpp

Lines changed: 1 addition & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -58,9 +58,6 @@ bool GazeboSystem::initSim(
5858
return false;
5959
}
6060

61-
// special handing since ODE uses a different set/get interface then the other engines
62-
usingODE = (physics_type_.compare("ode") == 0);
63-
6461
for (unsigned int j = 0; j < this->n_dof_; j++) {
6562
//
6663
// Perform some validation on the URDF joint and actuator spec
@@ -352,11 +349,7 @@ hardware_interface::return_type GazeboSystem::write()
352349
}
353350
break;
354351
case VELOCITY:
355-
if (usingODE) {
356-
sim_joints_[j]->SetParam("vel", 0, e_stop_active_ ? 0 : joint_velocity_cmd_[j]);
357-
} else {
358-
sim_joints_[j]->SetVelocity(0, e_stop_active_ ? 0 : joint_velocity_cmd_[j]);
359-
}
352+
sim_joints_[j]->SetVelocity(0, e_stop_active_ ? 0 : joint_velocity_cmd_[j]);
360353
break;
361354
case VELOCITY_PID:
362355
double error;

gazebo_ros2_control_demos/examples/example_velocity.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,7 @@ int main(int argc, char * argv[])
2828

2929
node = std::make_shared<rclcpp::Node>("velocity_test_node");
3030

31-
auto publisher = node->create_publisher<std_msgs::msg::Float64MultiArray>("/commands", 10);
31+
auto publisher = node->create_publisher<std_msgs::msg::Float64MultiArray>("/cart_pole_controller/commands", 10);
3232

3333
RCLCPP_INFO(node->get_logger(), "node created");
3434

0 commit comments

Comments
 (0)