Skip to content
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

[dynamixel_workbench_controllers] Enable to torque off on shutdown #386

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
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
5 changes: 5 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,11 @@
[![melodic-devel Status](https://github.com/ROBOTIS-GIT/dynamixel-workbench/workflows/melodic-devel/badge.svg)](https://github.com/ROBOTIS-GIT/dynamixel-workbench/tree/melodic-devel)
[![noetic-devel Status](https://github.com/ROBOTIS-GIT/dynamixel-workbench/workflows/noetic-devel/badge.svg)](https://github.com/ROBOTIS-GIT/dynamixel-workbench/tree/noetic-devel)

[![foxy-devel Status](https://github.com/ROBOTIS-GIT/dynamixel-workbench/workflows/foxy-devel/badge.svg)](https://github.com/ROBOTIS-GIT/dynamixel-workbench/tree/foxy-devel)
[![galactic-devel Status](https://github.com/ROBOTIS-GIT/dynamixel-workbench/workflows/galactic-devel/badge.svg)](https://github.com/ROBOTIS-GIT/dynamixel-workbench/tree/galactic-devel)
[![humble-devel Status](https://github.com/ROBOTIS-GIT/dynamixel-workbench/workflows/humble-devel/badge.svg)](https://github.com/ROBOTIS-GIT/dynamixel-workbench/tree/humble-devel)
[![ROS2 Rolling Status](https://github.com/ROBOTIS-GIT/dynamixel-workbench/workflows/ros2-ci/badge.svg)](https://github.com/ROBOTIS-GIT/dynamixel-workbench/tree/ros2)

## ROBOTIS e-Manual for Dynamixel Workbench
- [ROBOTIS e-Manual for Dynamixel Workbench](http://emanual.robotis.com/docs/en/software/dynamixel/dynamixel_workbench/)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,7 @@ class DynamixelController
bool is_joint_state_topic_;
bool is_cmd_vel_topic_;
bool use_moveit_;
bool torque_off_on_shutdown_;

double wheel_separation_;
double wheel_radius_;
Expand Down Expand Up @@ -126,6 +127,8 @@ class DynamixelController
void trajectoryMsgCallback(const trajectory_msgs::JointTrajectory::ConstPtr &msg);
bool dynamixelCommandMsgCallback(dynamixel_workbench_msgs::DynamixelCommand::Request &req,
dynamixel_workbench_msgs::DynamixelCommand::Response &res);

void onShutdown(void);
};

#endif //DYNAMIXEL_WORKBENCH_CONTROLLERS_H
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
<arg name="use_moveit" default="false"/>
<arg name="use_joint_state" default="true"/>
<arg name="use_cmd_vel" default="false"/>
<arg name="torque_off_on_shutdown" default="false"/>

<param name="dynamixel_info" value="$(find dynamixel_workbench_controllers)/config/basic.yaml"/>

Expand All @@ -14,6 +15,7 @@
<param name="use_moveit" value="$(arg use_moveit)"/>
<param name="use_joint_states_topic" value="$(arg use_joint_state)"/>
<param name="use_cmd_vel_topic" value="$(arg use_cmd_vel)"/>
<param name="torque_off_on_shutdown" value="$(arg torque_off_on_shutdown)"/>
<rosparam>
publish_period: 0.010
dxl_read_period: 0.010
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@ DynamixelController::DynamixelController()
is_joint_state_topic_ = priv_node_handle_.param<bool>("use_joint_states_topic", true);
is_cmd_vel_topic_ = priv_node_handle_.param<bool>("use_cmd_vel_topic", false);
use_moveit_ = priv_node_handle_.param<bool>("use_moveit", false);
torque_off_on_shutdown_ = priv_node_handle_.param<bool>("torque_off_on_shutdown", false);

read_period_ = priv_node_handle_.param<double>("dxl_read_period", 0.010f);
write_period_ = priv_node_handle_.param<double>("dxl_write_period", 0.010f);
Expand Down Expand Up @@ -762,6 +763,17 @@ bool DynamixelController::dynamixelCommandMsgCallback(dynamixel_workbench_msgs::
return true;
}

void DynamixelController::onShutdown()
{
if (torque_off_on_shutdown_ == true)
{
for (auto const& dxl:dynamixel_)
{
dxl_wb_->torqueOff((uint8_t)dxl.second);
}
}
}

int main(int argc, char **argv)
{
ros::init(argc, argv, "dynamixel_workbench_controllers");
Expand Down Expand Up @@ -839,5 +851,7 @@ int main(int argc, char **argv)

ros::spin();

dynamixel_controller.onShutdown();

return 0;
}