diff --git a/README.md b/README.md
index 1b7bace8..605b81a7 100644
--- a/README.md
+++ b/README.md
@@ -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/)
diff --git a/dynamixel_workbench_controllers/include/dynamixel_workbench_controllers/dynamixel_workbench_controllers.h b/dynamixel_workbench_controllers/include/dynamixel_workbench_controllers/dynamixel_workbench_controllers.h
index a2f08979..a94b98c5 100644
--- a/dynamixel_workbench_controllers/include/dynamixel_workbench_controllers/dynamixel_workbench_controllers.h
+++ b/dynamixel_workbench_controllers/include/dynamixel_workbench_controllers/dynamixel_workbench_controllers.h
@@ -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_;
@@ -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
diff --git a/dynamixel_workbench_controllers/launch/dynamixel_controllers.launch b/dynamixel_workbench_controllers/launch/dynamixel_controllers.launch
index 695c5274..a81983cf 100644
--- a/dynamixel_workbench_controllers/launch/dynamixel_controllers.launch
+++ b/dynamixel_workbench_controllers/launch/dynamixel_controllers.launch
@@ -6,6 +6,7 @@
+
@@ -14,6 +15,7 @@
+
publish_period: 0.010
dxl_read_period: 0.010
diff --git a/dynamixel_workbench_controllers/src/dynamixel_workbench_controllers.cpp b/dynamixel_workbench_controllers/src/dynamixel_workbench_controllers.cpp
index 13d5427c..56e51736 100644
--- a/dynamixel_workbench_controllers/src/dynamixel_workbench_controllers.cpp
+++ b/dynamixel_workbench_controllers/src/dynamixel_workbench_controllers.cpp
@@ -31,6 +31,7 @@ DynamixelController::DynamixelController()
is_joint_state_topic_ = priv_node_handle_.param("use_joint_states_topic", true);
is_cmd_vel_topic_ = priv_node_handle_.param("use_cmd_vel_topic", false);
use_moveit_ = priv_node_handle_.param("use_moveit", false);
+ torque_off_on_shutdown_ = priv_node_handle_.param("torque_off_on_shutdown", false);
read_period_ = priv_node_handle_.param("dxl_read_period", 0.010f);
write_period_ = priv_node_handle_.param("dxl_write_period", 0.010f);
@@ -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");
@@ -839,5 +851,7 @@ int main(int argc, char **argv)
ros::spin();
+ dynamixel_controller.onShutdown();
+
return 0;
}