00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include "pr2_gazebo_benchmarks/joint_pendulum_controller.h"
00036 #include "angles/angles.h"
00037 #include "pluginlib/class_list_macros.h"
00038
00039 PLUGINLIB_DECLARE_CLASS(pr2_gazebo_benchmarks, JointPendulumController, controller::JointPendulumController, pr2_controller_interface::Controller)
00040
00041 using namespace std;
00042
00043 namespace controller {
00044
00045 JointPendulumController::JointPendulumController()
00046 : joint_state_(NULL), command_(0),
00047 loop_count_(0), initialized_(false), robot_(NULL), last_time_(0), last_position_(0), last_last_position_(0)
00048 {
00049 }
00050
00051 JointPendulumController::~JointPendulumController()
00052 {
00053 sub_command_.shutdown();
00054 }
00055
00056 bool JointPendulumController::init(pr2_mechanism_model::RobotState *robot, const std::string &joint_name,
00057 const control_toolbox::Pid &pid)
00058 {
00059 assert(robot);
00060 robot_ = robot;
00061 last_time_ = robot->getTime();
00062
00063 joint_state_ = robot_->getJointState(joint_name);
00064 if (!joint_state_)
00065 {
00066 ROS_ERROR("JointPendulumController could not find joint named \"%s\"\n",
00067 joint_name.c_str());
00068 return false;
00069 }
00070 if (!joint_state_->calibrated_)
00071 {
00072 ROS_ERROR("Joint %s not calibrated for JointPendulumController", joint_name.c_str());
00073 return false;
00074 }
00075
00076 pid_controller_ = pid;
00077
00078 return true;
00079 }
00080
00081 bool JointPendulumController::init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
00082 {
00083 assert(robot);
00084 node_ = n;
00085
00086 std::string joint_name;
00087 if (!node_.getParam("joint", joint_name)) {
00088 ROS_ERROR("No joint given (namespace: %s)", node_.getNamespace().c_str());
00089 return false;
00090 }
00091
00092 control_toolbox::Pid pid;
00093 if (!pid.init(ros::NodeHandle(node_, "pid")))
00094 return false;
00095
00096 controller_state_publisher_.reset(
00097 new realtime_tools::RealtimePublisher<pr2_controllers_msgs::JointControllerState>
00098 (node_, "state", 1));
00099
00100 sub_command_ = node_.subscribe<std_msgs::Float64>("command", 1, &JointPendulumController::setCommandCB, this);
00101
00102 return init(robot, joint_name, pid);
00103 }
00104
00105
00106 void JointPendulumController::setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min)
00107 {
00108 pid_controller_.setGains(p,i,d,i_max,i_min);
00109 }
00110
00111 void JointPendulumController::getGains(double &p, double &i, double &d, double &i_max, double &i_min)
00112 {
00113 pid_controller_.getGains(p,i,d,i_max,i_min);
00114 }
00115
00116 std::string JointPendulumController::getJointName()
00117 {
00118 return joint_state_->joint_->name;
00119 }
00120
00121
00122 void JointPendulumController::setCommand(double cmd)
00123 {
00124 command_ = cmd;
00125 }
00126
00127
00128 void JointPendulumController::getCommand(double & cmd)
00129 {
00130 cmd = command_;
00131 }
00132
00133 void JointPendulumController::update()
00134 {
00135 if (!joint_state_->calibrated_)
00136 return;
00137
00138 assert(robot_ != NULL);
00139 double error(0);
00140 ros::Time time = robot_->getTime();
00141 assert(joint_state_->joint_);
00142 dt_= time - last_time_;
00143
00144 if (!initialized_)
00145 {
00146 initialized_ = true;
00147 command_ = joint_state_->position_;
00148 last_position_ = joint_state_->position_;
00149 last_last_position_ = joint_state_->position_;
00150 }
00151
00152 if(joint_state_->joint_->type == urdf::Joint::REVOLUTE)
00153 {
00154 error = joint_state_->position_ - command_;
00155 }
00156 else if(joint_state_->joint_->type == urdf::Joint::CONTINUOUS)
00157 {
00158 error = angles::shortest_angular_distance(command_, joint_state_->position_);
00159 }
00160 else
00161 {
00162 error = joint_state_->position_ - command_;
00163 }
00164
00165 double commanded_effort = pid_controller_.updatePid(error, dt_);
00166
00167
00168
00169 double g = 1.0;
00170 double p = angles::shortest_angular_distance(joint_state_->position_,M_PI/2.0);
00171
00172
00173
00174
00175
00176
00177
00178
00179
00180
00181
00182
00183 double m = 1;
00184 double l = 1;
00185 double I = m*l*l;
00186
00187
00188 bool nj = 1000;
00189 ros::Time tau = time;
00190 double dtau = dt_.toSec() / (double)nj;
00191 double theta = last_position_;
00192
00193 for (int j=0;j<nj;j++)
00194 {
00195
00196 theta = theta + dtau * ( (last_position_ - last_last_position_) / dt_.toSec()
00197 - 0.5 * (dtau + dt_.toSec()) *m * g * l / I * sin(theta) ) ;
00198 }
00199 ROS_WARN("pendulum %20.15f %20.15f",joint_state_->position_,joint_state_->position_ - theta);
00200
00201
00202
00203 if(loop_count_ % 10 == 0)
00204 {
00205 if(controller_state_publisher_ && controller_state_publisher_->trylock())
00206 {
00207 controller_state_publisher_->msg_.header.stamp = time;
00208 controller_state_publisher_->msg_.set_point = command_;
00209 controller_state_publisher_->msg_.process_value = joint_state_->position_;
00210 controller_state_publisher_->msg_.process_value_dot = joint_state_->velocity_;
00211 controller_state_publisher_->msg_.error = error;
00212 controller_state_publisher_->msg_.time_step = dt_.toSec();
00213 controller_state_publisher_->msg_.command = commanded_effort;
00214
00215 double dummy;
00216 getGains(controller_state_publisher_->msg_.p,
00217 controller_state_publisher_->msg_.i,
00218 controller_state_publisher_->msg_.d,
00219 controller_state_publisher_->msg_.i_clamp,
00220 dummy);
00221 controller_state_publisher_->unlockAndPublish();
00222 }
00223 }
00224 loop_count_++;
00225
00226 last_time_ = time;
00227 last_last_position_ = last_position_;
00228 last_position_ = joint_state_->position_;
00229 }
00230
00231 void JointPendulumController::setCommandCB(const std_msgs::Float64ConstPtr& msg)
00232 {
00233 command_ = msg->data;
00234 }
00235
00236 }