1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-10 10:00:48 +02:00

Fixed order of starting and stopping controllers

This commit is contained in:
Thomas Timm Andersen
2015-09-25 10:19:58 +02:00
parent dc49deaf18
commit 68b751cdcc
4 changed files with 25 additions and 25 deletions

View File

@@ -30,11 +30,11 @@
<rosparam file="$(find ur_modern_driver)/config/ur5_controllers.yaml" command="load"/> <rosparam file="$(find ur_modern_driver)/config/ur5_controllers.yaml" command="load"/>
<!-- spawn controller manager --> <!-- spawn controller manager -->
<node name="ros_control_controller_manager" pkg="controller_manager" type="spawner" respawn="false" <node name="ros_control_controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
output="screen" args="joint_state_controller force_torque_sensor_controller position_based_position_trajectory_controller" /> output="screen" args="joint_state_controller force_torque_sensor_controller velocity_based_position_trajectory_controller" />
<!-- load other controller --> <!-- load other controller -->
<node name="ros_control_controller_manager" pkg="controller_manager" type="controller_manager" respawn="false" <node name="ros_control_controller_manager" pkg="controller_manager" type="controller_manager" respawn="false"
output="screen" args="load velocity_based_position_trajectory_controller" /> output="screen" args="load position_based_position_trajectory_controller" />
<!-- Convert joint states to /tf tranforms --> <!-- Convert joint states to /tf tranforms -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/> <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>

View File

@@ -9,39 +9,39 @@
* ---------------------------------------------------------------------------- * ----------------------------------------------------------------------------
*/ */
#include "ur_modern_driver/du_output.h" #include "ur_modern_driver/do_output.h"
void print_debug(std::string inp) { void print_debug(std::string inp) {
#ifdef ROS_BUILD #ifdef ROS_BUILD
ROS_DEBUG(inp); ROS_DEBUG(inp.c_str());
#else #else
printf("DEBUG: %s\n", inp.c_str()); printf("DEBUG: %s\n", inp.c_str());
#endif #endif
} }
void print_info(std::string inp) { void print_info(std::string inp) {
#ifdef ROS_BUILD #ifdef ROS_BUILD
ROS_INFO(inp); ROS_INFO(inp.c_str());
#else #else
printf("INFO: %s\n", inp.c_str()); printf("INFO: %s\n", inp.c_str());
#endif #endif
} }
void print_warning(std::string inp) { void print_warning(std::string inp) {
#ifdef ROS_BUILD #ifdef ROS_BUILD
ROS_WARN(inp); ROS_WARN(inp.c_str());
#else #else
printf("WARNING: %s\n", inp.c_str()); printf("WARNING: %s\n", inp.c_str());
#endif #endif
} }
void print_error(std::string inp) { void print_error(std::string inp) {
#ifdef ROS_BUILD #ifdef ROS_BUILD
ROS_ERROR(inp); ROS_ERROR(inp.c_str());
#else #else
printf("ERROR: %s\n", inp.c_str()); printf("ERROR: %s\n", inp.c_str());
#endif #endif
} }
void print_fatal(std::string inp) { void print_fatal(std::string inp) {
#ifdef ROS_BUILD #ifdef ROS_BUILD
ROS_FATAL(inp); ROS_FATAL(inp.c_str());
ros::shutdown(); ros::shutdown();
#else #else
printf("FATAL: %s\n", inp.c_str()); printf("FATAL: %s\n", inp.c_str());

View File

@@ -257,7 +257,6 @@ void UrDriver::uploadProg() {
cmd_str += "end\n"; cmd_str += "end\n";
rt_interface_->addCommandToQueue(cmd_str); rt_interface_->addCommandToQueue(cmd_str);
UrDriver::openServo(); UrDriver::openServo();
} }

View File

@@ -211,6 +211,7 @@ bool UrHardwareInterface::canSwitch(
} }
} }
} }
// we can always stop a controller // we can always stop a controller
return true; return true;
} }
@@ -218,21 +219,6 @@ bool UrHardwareInterface::canSwitch(
void UrHardwareInterface::doSwitch( void UrHardwareInterface::doSwitch(
const std::list<hardware_interface::ControllerInfo>& start_list, const std::list<hardware_interface::ControllerInfo>& start_list,
const std::list<hardware_interface::ControllerInfo>& stop_list) { const std::list<hardware_interface::ControllerInfo>& stop_list) {
for (std::list<hardware_interface::ControllerInfo>::const_iterator controller_it =
start_list.begin(); controller_it != start_list.end();
++controller_it) {
if (controller_it->hardware_interface
== "hardware_interface::VelocityJointInterface") {
velocity_interface_running_ = true;
ROS_DEBUG("Starting velocity interface");
}
if (controller_it->hardware_interface
== "hardware_interface::PositionJointInterface") {
position_interface_running_ = true;
robot_->uploadProg();
ROS_DEBUG("Starting position interface");
}
}
for (std::list<hardware_interface::ControllerInfo>::const_iterator controller_it = for (std::list<hardware_interface::ControllerInfo>::const_iterator controller_it =
stop_list.begin(); controller_it != stop_list.end(); stop_list.begin(); controller_it != stop_list.end();
++controller_it) { ++controller_it) {
@@ -249,6 +235,21 @@ void UrHardwareInterface::doSwitch(
ROS_DEBUG("Stopping position interface"); ROS_DEBUG("Stopping position interface");
} }
} }
for (std::list<hardware_interface::ControllerInfo>::const_iterator controller_it =
start_list.begin(); controller_it != start_list.end();
++controller_it) {
if (controller_it->hardware_interface
== "hardware_interface::VelocityJointInterface") {
velocity_interface_running_ = true;
ROS_DEBUG("Starting velocity interface");
}
if (controller_it->hardware_interface
== "hardware_interface::PositionJointInterface") {
position_interface_running_ = true;
robot_->uploadProg();
ROS_DEBUG("Starting position interface");
}
}
} }