Skip to content

Commit

Permalink
Bugfix variables used in trick_system (#42).
Browse files Browse the repository at this point in the history
  • Loading branch information
bfidegh committed Feb 12, 2025
1 parent 6f70dd3 commit 773f7c3
Showing 1 changed file with 4 additions and 4 deletions.
8 changes: 4 additions & 4 deletions ros_trick/ros_src/trick_ros2_control/src/trick_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -177,19 +177,19 @@ std::vector<hardware_interface::CommandInterface> TrickSystem::export_command_in
std::string joint_interface_name = joint_info.command_interfaces[j].name;
if (joint_interface_name == hardware_interface::HW_IF_POSITION)
{
command_variable_ptr_ = &joints_data_[i].joint_position;
command_variable_ptr_ = &joints_data_[i].joint_position_cmd;
}
if (joint_interface_name == hardware_interface::HW_IF_VELOCITY)
{
command_variable_ptr_ = &joints_data_[i].joint_velocity;
command_variable_ptr_ = &joints_data_[i].joint_velocity_cmd;
}
if (joint_interface_name == hardware_interface::HW_IF_ACCELERATION)
{
command_variable_ptr_ = &joints_data_[i].joint_acceleration;
command_variable_ptr_ = &joints_data_[i].joint_acceleration_cmd;
}
if (joint_interface_name == hardware_interface::HW_IF_EFFORT)
{
command_variable_ptr_ = &joints_data_[i].joint_effort;
command_variable_ptr_ = &joints_data_[i].joint_effort_cmd;
}
// TODO(later) - parametrize it with joint params
*command_variable_ptr_ = 0.0;
Expand Down

0 comments on commit 773f7c3

Please sign in to comment.