Skip to content

Commit a5957fc

Browse files
author
Felix Exner
committed
Remove unused interfaces
1 parent e513fc6 commit a5957fc

File tree

2 files changed

+5
-8
lines changed

2 files changed

+5
-8
lines changed

ur_robot_driver/include/ur_robot_driver/hardware_interface.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -200,7 +200,7 @@ class URPositionHardwareInterface : public hardware_interface::SystemInterface
200200
// Passthrough trajectory controller interface values
201201
double passthrough_trajectory_transfer_state_;
202202
double passthrough_trajectory_abort_;
203-
double passthrough_trajectory_controller_running_;
203+
bool passthrough_trajectory_controller_running_;
204204
urcl::vector6d_t passthrough_trajectory_positions_;
205205
urcl::vector6d_t passthrough_trajectory_velocities_;
206206
urcl::vector6d_t passthrough_trajectory_accelerations_;

ur_robot_driver/src/hardware_interface.cpp

Lines changed: 4 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -236,9 +236,6 @@ std::vector<hardware_interface::StateInterface> URPositionHardwareInterface::exp
236236
state_interfaces.emplace_back(
237237
hardware_interface::StateInterface(tf_prefix + "gpio", "program_running", &robot_program_running_copy_));
238238

239-
state_interfaces.emplace_back(hardware_interface::StateInterface(tf_prefix + "passthrough_controller", "running",
240-
&passthrough_trajectory_controller_running_));
241-
242239
return state_interfaces;
243240
}
244241

@@ -911,7 +908,7 @@ hardware_interface::return_type URPositionHardwareInterface::perform_command_mod
911908
urcl_velocity_commands_ = { { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 } };
912909
} else if (stop_modes_.size() != 0 && std::find(stop_modes_.begin(), stop_modes_.end(),
913910
StoppingInterface::STOP_PASSTHROUGH) != stop_modes_.end()) {
914-
passthrough_trajectory_controller_running_ = 0.0;
911+
passthrough_trajectory_controller_running_ = false;
915912
passthrough_trajectory_abort_ = 1.0;
916913
trajectory_joint_positions_.clear();
917914
trajectory_joint_accelerations_.clear();
@@ -921,21 +918,21 @@ hardware_interface::return_type URPositionHardwareInterface::perform_command_mod
921918
if (start_modes_.size() != 0 &&
922919
std::find(start_modes_.begin(), start_modes_.end(), hardware_interface::HW_IF_POSITION) != start_modes_.end()) {
923920
velocity_controller_running_ = false;
924-
passthrough_trajectory_controller_running_ = 0.0;
921+
passthrough_trajectory_controller_running_ = false;
925922
urcl_position_commands_ = urcl_position_commands_old_ = urcl_joint_positions_;
926923
position_controller_running_ = true;
927924

928925
} else if (start_modes_.size() != 0 && std::find(start_modes_.begin(), start_modes_.end(),
929926
hardware_interface::HW_IF_VELOCITY) != start_modes_.end()) {
930927
position_controller_running_ = false;
931-
passthrough_trajectory_controller_running_ = 0.0;
928+
passthrough_trajectory_controller_running_ = false;
932929
urcl_velocity_commands_ = { { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 } };
933930
velocity_controller_running_ = true;
934931
} else if (start_modes_.size() != 0 && std::find(start_modes_.begin(), start_modes_.end(),
935932
PASSTHROUGH_TRAJECTORY_CONTROLLER) != start_modes_.end()) {
936933
velocity_controller_running_ = false;
937934
position_controller_running_ = false;
938-
passthrough_trajectory_controller_running_ = 1.0;
935+
passthrough_trajectory_controller_running_ = true;
939936
}
940937

941938
start_modes_.clear();

0 commit comments

Comments
 (0)