Skip to content

Swap Position to ExtendedPosition mode #1

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 1 commit into from
Feb 13, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 8 additions & 8 deletions dynamixel_hardware/src/dynamixel_hardware.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ CallbackReturn DynamixelHardware::on_init(const hardware_interface::HardwareInfo
}

enable_torque(false);
set_control_mode(ControlMode::Position, true);
set_control_mode(ControlMode::ExtendedPosition, true);
set_joint_params();
enable_torque(true);

Expand Down Expand Up @@ -305,7 +305,7 @@ return_type DynamixelHardware::write(const rclcpp::Time & /* time */, const rclc
// Position control
if (std::any_of(
joints_.cbegin(), joints_.cend(), [](auto j) { return j.command.position != j.prev_command.position; })) {
set_control_mode(ControlMode::Position);
set_control_mode(ControlMode::ExtendedPosition);
if(mode_changed_)
{
set_joint_params();
Expand All @@ -327,7 +327,7 @@ return_type DynamixelHardware::write(const rclcpp::Time & /* time */, const rclc
set_joint_velocities();
return return_type::OK;
break;
case ControlMode::Position:
case ControlMode::ExtendedPosition:
set_joint_positions();
return return_type::OK;
break;
Expand Down Expand Up @@ -396,23 +396,23 @@ return_type DynamixelHardware::set_control_mode(const ControlMode & mode, const
return return_type::OK;
}

if (mode == ControlMode::Position && (force_set || control_mode_ != ControlMode::Position)) {
if (mode == ControlMode::ExtendedPosition && (force_set || control_mode_ != ControlMode::ExtendedPosition)) {
bool torque_enabled = torque_enabled_;
if (torque_enabled) {
enable_torque(false);
}

for (uint i = 0; i < joint_ids_.size(); ++i) {
if (!dynamixel_workbench_.setPositionControlMode(joint_ids_[i], &log)) {
if (!dynamixel_workbench_.setExtendedPositionControlMode(joint_ids_[i], &log)) {
RCLCPP_FATAL(rclcpp::get_logger(kDynamixelHardware), "%s", log);
return return_type::ERROR;
}
}
RCLCPP_INFO(rclcpp::get_logger(kDynamixelHardware), "Position control");
if(control_mode_ != ControlMode::Position)
if(control_mode_ != ControlMode::ExtendedPosition)
{
mode_changed_ = true;
control_mode_ = ControlMode::Position;
control_mode_ = ControlMode::ExtendedPosition;
}

if (torque_enabled) {
Expand All @@ -421,7 +421,7 @@ return_type DynamixelHardware::set_control_mode(const ControlMode & mode, const
return return_type::OK;
}

if (control_mode_ != ControlMode::Velocity && control_mode_ != ControlMode::Position) {
if (control_mode_ != ControlMode::Velocity && control_mode_ != ControlMode::ExtendedPosition) {
RCLCPP_FATAL(
rclcpp::get_logger(kDynamixelHardware), "Only position/velocity control are implemented");
return return_type::ERROR;
Expand Down