diff --git a/effort_controllers/src/joint_effort_controller.cpp b/effort_controllers/src/joint_effort_controller.cpp index 75248f280..b05d64a88 100644 --- a/effort_controllers/src/joint_effort_controller.cpp +++ b/effort_controllers/src/joint_effort_controller.cpp @@ -41,7 +41,7 @@ template void forward_command_controller::ForwardCommandController::starting(const ros::Time& time) { // Start controller with 0.0 effort - command_ = 0.0; + command_buffer_.writeFromNonRT(0.0); } diff --git a/effort_controllers/src/joint_group_effort_controller.cpp b/effort_controllers/src/joint_group_effort_controller.cpp index f90c8e0cc..bf41e3c91 100644 --- a/effort_controllers/src/joint_group_effort_controller.cpp +++ b/effort_controllers/src/joint_group_effort_controller.cpp @@ -42,7 +42,7 @@ template void forward_command_controller::ForwardJointGroupCommandController::starting(const ros::Time& time) { // Start controller with 0.0 efforts - commands_.resize(n_joints_, 0.0); + commands_buffer_.readFromRT()->assign(n_joints_, 0.0); } diff --git a/forward_command_controller/CMakeLists.txt b/forward_command_controller/CMakeLists.txt index a2af904a0..891dc83e4 100644 --- a/forward_command_controller/CMakeLists.txt +++ b/forward_command_controller/CMakeLists.txt @@ -2,11 +2,11 @@ cmake_minimum_required(VERSION 2.8.3) project(forward_command_controller) # Load catkin and all dependencies required for this package -find_package(catkin REQUIRED COMPONENTS controller_interface hardware_interface std_msgs) +find_package(catkin REQUIRED COMPONENTS controller_interface hardware_interface std_msgs realtime_tools) # Declare catkin package catkin_package( - CATKIN_DEPENDS controller_interface hardware_interface std_msgs + CATKIN_DEPENDS controller_interface hardware_interface std_msgs realtime_tools INCLUDE_DIRS include ) diff --git a/forward_command_controller/include/forward_command_controller/forward_command_controller.h b/forward_command_controller/include/forward_command_controller/forward_command_controller.h index 30c5dd3c4..621dd8fa4 100644 --- a/forward_command_controller/include/forward_command_controller/forward_command_controller.h +++ b/forward_command_controller/include/forward_command_controller/forward_command_controller.h @@ -42,6 +42,7 @@ #include #include #include +#include namespace forward_command_controller @@ -68,7 +69,7 @@ template class ForwardCommandController: public controller_interface::Controller { public: - ForwardCommandController() : command_(0) {} + ForwardCommandController() {} ~ForwardCommandController() {sub_command_.shutdown();} bool init(T* hw, ros::NodeHandle &n) @@ -85,14 +86,14 @@ class ForwardCommandController: public controller_interface::Controller } void starting(const ros::Time& time); - void update(const ros::Time& time, const ros::Duration& period) {joint_.setCommand(command_);} + void update(const ros::Time& time, const ros::Duration& period) {joint_.setCommand(*command_buffer_.readFromRT());} hardware_interface::JointHandle joint_; - double command_; + realtime_tools::RealtimeBuffer command_buffer_; private: ros::Subscriber sub_command_; - void commandCB(const std_msgs::Float64ConstPtr& msg) {command_ = msg->data;} + void commandCB(const std_msgs::Float64ConstPtr& msg) {command_buffer_.writeFromNonRT(msg->data);} }; } diff --git a/forward_command_controller/include/forward_command_controller/forward_joint_group_command_controller.h b/forward_command_controller/include/forward_command_controller/forward_joint_group_command_controller.h index bb69215d3..8dedc0cec 100644 --- a/forward_command_controller/include/forward_command_controller/forward_joint_group_command_controller.h +++ b/forward_command_controller/include/forward_command_controller/forward_joint_group_command_controller.h @@ -46,6 +46,7 @@ #include #include #include +#include namespace forward_command_controller @@ -72,7 +73,7 @@ template class ForwardJointGroupCommandController: public controller_interface::Controller { public: - ForwardJointGroupCommandController() { commands_.clear(); } + ForwardJointGroupCommandController() {} ~ForwardJointGroupCommandController() {sub_command_.shutdown();} bool init(T* hw, ros::NodeHandle &n) @@ -85,7 +86,11 @@ class ForwardJointGroupCommandController: public controller_interface::Controlle return false; } n_joints_ = joint_names_.size(); - + + if(n_joints_ == 0){ + ROS_ERROR_STREAM("List of joint names is empty."); + return false; + } for(unsigned int i=0; i(n_joints_, 0.0)); + sub_command_ = n.subscribe("command", 1, &ForwardJointGroupCommandController::commandCB, this); return true; } @@ -106,13 +113,14 @@ class ForwardJointGroupCommandController: public controller_interface::Controlle void starting(const ros::Time& time); void update(const ros::Time& time, const ros::Duration& period) { + std::vector & commands = *commands_buffer_.readFromRT(); for(unsigned int i=0; i joint_names_; std::vector< hardware_interface::JointHandle > joints_; - std::vector< double > commands_; + realtime_tools::RealtimeBuffer > commands_buffer_; unsigned int n_joints_; private: @@ -124,8 +132,7 @@ class ForwardJointGroupCommandController: public controller_interface::Controlle ROS_ERROR_STREAM("Dimension of command (" << msg->data.size() << ") does not match number of joints (" << n_joints_ << ")! Not executing!"); return; } - for(unsigned int i=0; idata[i]; } + commands_buffer_.writeFromNonRT(msg->data); } }; diff --git a/forward_command_controller/package.xml b/forward_command_controller/package.xml index d9a9bf4fe..7884ede0a 100644 --- a/forward_command_controller/package.xml +++ b/forward_command_controller/package.xml @@ -16,10 +16,12 @@ catkin controller_interface hardware_interface - std_msgs + std_msgs + realtime_tools controller_interface hardware_interface std_msgs + realtime_tools diff --git a/position_controllers/src/joint_group_position_controller.cpp b/position_controllers/src/joint_group_position_controller.cpp index 9ad7a579a..ee88966df 100644 --- a/position_controllers/src/joint_group_position_controller.cpp +++ b/position_controllers/src/joint_group_position_controller.cpp @@ -42,10 +42,10 @@ template void forward_command_controller::ForwardJointGroupCommandController::starting(const ros::Time& time) { // Start controller with current joint positions - commands_.resize(n_joints_, 0.0); + std::vector & commands = *commands_buffer_.readFromRT(); for(unsigned int i=0; i void forward_command_controller::ForwardCommandController::starting(const ros::Time& time) { // Start controller with current joint position - command_ = joint_.getPosition(); + command_buffer_.writeFromNonRT(joint_.getPosition()); } PLUGINLIB_EXPORT_CLASS(position_controllers::JointPositionController,controller_interface::ControllerBase) diff --git a/velocity_controllers/src/joint_group_velocity_controller.cpp b/velocity_controllers/src/joint_group_velocity_controller.cpp index 158c1cb83..715ca746f 100644 --- a/velocity_controllers/src/joint_group_velocity_controller.cpp +++ b/velocity_controllers/src/joint_group_velocity_controller.cpp @@ -42,7 +42,7 @@ template void forward_command_controller::ForwardJointGroupCommandController::starting(const ros::Time& time) { // Start controller with 0.0 velocities - commands_.resize(n_joints_, 0.0); + commands_buffer_.readFromRT()->assign(n_joints_, 0.0); } diff --git a/velocity_controllers/src/joint_velocity_controller.cpp b/velocity_controllers/src/joint_velocity_controller.cpp index f4f3a93ce..3b1970ad0 100644 --- a/velocity_controllers/src/joint_velocity_controller.cpp +++ b/velocity_controllers/src/joint_velocity_controller.cpp @@ -41,7 +41,7 @@ template void forward_command_controller::ForwardCommandController::starting(const ros::Time& time) { // Start controller with 0.0 velocity - command_ = 0.0; + command_buffer_.writeFromNonRT(0.0); }