Go to the documentation of this file.00001
00027 #include "../example/srh_example_controller.hpp"
00028 #include <angles/angles.h>
00029 #include <pluginlib/class_list_macros.h>
00030
00031 #include <std_msgs/Float64.h>
00032
00033
00034 PLUGINLIB_EXPORT_CLASS( controller::SrhExampleController, controller_interface::ControllerBase)
00035
00036 using namespace std;
00037
00038 namespace controller {
00039
00040 SrhExampleController::SrhExampleController()
00041 : SrController()
00042 {
00043
00044
00045 }
00046
00047 SrhExampleController::~SrhExampleController()
00048 {
00049
00050 sub_command_.shutdown();
00051 }
00052
00053 bool SrhExampleController::init(ros_ethercat_model::RobotState *robot, ros::NodeHandle &n)
00054 {
00055 assert(robot);
00056 node_ = n;
00057
00058
00059 std::string joint_name;
00060 if (!node_.getParam("joint", joint_name)) {
00061 ROS_ERROR("No joint given (namespace: %s)", node_.getNamespace().c_str());
00062 return false;
00063 }
00064
00065
00066
00067
00068
00069
00070 controller_state_publisher_.reset(
00071 new realtime_tools::RealtimePublisher<control_msgs::JointControllerState>
00072 (node_, "state", 1));
00073
00074
00075 return init(robot, joint_name);
00076 }
00077
00078 bool SrhExampleController::init(ros_ethercat_model::RobotState *robot, const std::string &joint_name)
00079 {
00080 assert(robot);
00081 robot_ = robot;
00082
00083
00084
00085 if( joint_name.substr(3,1).compare("0") == 0)
00086 {
00087 has_j2 = true;
00088
00089
00090 std::string j1 = joint_name.substr(0,3) + "1";
00091 std::string j2 = joint_name.substr(0,3) + "2";
00092
00093
00094 joint_state_ = robot_->getJointState(j1);
00095 if (!joint_state_)
00096 {
00097 ROS_ERROR("SrhMixedPositionVelocityController could not find joint named \"%s\"\n",
00098 joint_name.c_str());
00099 return false;
00100 }
00101
00102
00103 joint_state_2 = robot_->getJointState(j2);
00104 if (!joint_state_2)
00105 {
00106 ROS_ERROR("SrhMixedPositionVelocityController could not find joint named \"%s\"\n",
00107 joint_name.c_str());
00108 return false;
00109 }
00110 }
00111 else
00112 {
00113 has_j2 = false;
00114
00115
00116 joint_state_ = robot_->getJointState(joint_name);
00117 if (!joint_state_)
00118 {
00119 ROS_ERROR("SrhMixedPositionVelocityController could not find joint named \"%s\"\n",
00120 joint_name.c_str());
00121 return false;
00122 }
00123 }
00124
00125
00126 after_init();
00127 return true;
00128 }
00129
00130
00131 void SrhExampleController::starting(const ros::Time& time)
00132 {
00133
00134 if( has_j2 )
00135 command_ = joint_state_->position_ + joint_state_2->position_;
00136 else
00137 command_ = joint_state_->position_;
00138 }
00139
00140 void SrhExampleController::update(const ros::Time& time, const ros::Duration& period)
00141 {
00142 assert(robot_ != NULL);
00143 assert(joint_state_->joint_);
00144
00145
00146
00147 if (!initialized_)
00148 {
00149 starting(time);
00150
00151 initialized_ = true;
00152 }
00153
00154
00155
00156
00157
00158
00159
00160
00161
00162 double error_position = 0.0;
00163 if( has_j2 )
00164 {
00165
00166 error_position = command_ - (joint_state_->position_ + joint_state_2->position_);
00167 }
00168 else
00169 error_position = command_ - joint_state_->position_;
00170
00171
00172
00173
00174 double commanded_effort = 10* error_position;
00175
00176
00177 if( has_j2 )
00178 joint_state_2->commanded_effort_ = commanded_effort;
00179 else
00180 joint_state_->commanded_effort_ = commanded_effort;
00181
00182 if(loop_count_ % 10 == 0)
00183 {
00184 if(controller_state_publisher_ && controller_state_publisher_->trylock())
00185 {
00186 controller_state_publisher_->msg_.header.stamp = time;
00187 controller_state_publisher_->msg_.set_point = command_;
00188
00189 if( has_j2 )
00190 {
00191 controller_state_publisher_->msg_.process_value = joint_state_->position_ + joint_state_2->position_;
00192 controller_state_publisher_->msg_.process_value_dot = joint_state_->velocity_ + joint_state_2->velocity_;
00193 }
00194 else
00195 {
00196 controller_state_publisher_->msg_.process_value = joint_state_->position_;
00197 controller_state_publisher_->msg_.process_value_dot = joint_state_->velocity_;
00198 }
00199
00200 controller_state_publisher_->msg_.error = error_position;
00201 controller_state_publisher_->msg_.time_step = period.toSec();
00202 controller_state_publisher_->msg_.command = commanded_effort;
00203
00204 controller_state_publisher_->unlockAndPublish();
00205 }
00206 }
00207 loop_count_++;
00208 }
00209 }
00210
00211
00212
00213
00214
00215
00216
00217