00001
00002
00003
00004
00005
00006
00007
00020 #include <ros/ros.h>
00021 #include <art/pid2.h>
00022 #include <art_msgs/Epsilon.h>
00023
00024 #include "accel_example.h"
00025
00026 using art_msgs::Epsilon;
00027
00028 namespace pilot
00029 {
00030
00031 AccelExample::AccelExample(art_pilot::PilotConfig &config):
00032 AccelBase(config),
00033 braking_(true),
00034 brake_pid_(new Pid("brake", config.brake_kp, config.brake_ki,
00035 config.brake_kd, 1.0, 0.0, 5000.0)),
00036 throttle_pid_(new Pid("throttle", config.throttle_kp, config.throttle_ki,
00037 config.throttle_kd, 0.4, 0.0, 5000.0))
00038 {
00039 reset();
00040 };
00041
00042 AccelExample::~AccelExample() {};
00043
00044 void AccelExample::adjust(art_msgs::PilotState &pstate,
00045 ServoPtr brake, ServoPtr throttle)
00046 {
00047 float brake_request;
00048 float throttle_request;
00049 float abs_speed = fabs(pstate.current.speed);
00050 float error = fabs(pstate.target.speed) - abs_speed;
00051
00052 if (braking_)
00053 {
00054
00055 brake_request = brake_pid_->Update(error, abs_speed);
00056 throttle_request = 0.0;
00057
00058
00059
00060
00061
00062
00063
00064 if ((brake->value() < Epsilon::brake_position)
00065 && (brake_request < Epsilon::brake_position))
00066 {
00067 brake_request = 0.0;
00068 braking_ = false;
00069 throttle_pid_->Clear();
00070 }
00071 }
00072 else
00073 {
00074
00075 throttle_request = throttle_pid_->Update(error, abs_speed);
00076 brake_request = 0.0;
00077
00078
00079
00080
00081
00082
00083
00084 if (throttle_request < Epsilon::throttle_position)
00085 {
00086 throttle_request = 0.0;
00087 braking_ = true;
00088 brake_pid_->Clear();
00089 }
00090 }
00091
00092 brake_request = clamp(0.0, brake_request, 1.0);
00093 if (fabsf(brake_request - brake->value()) > Epsilon::brake_position)
00094 {
00095 brake->publish(brake_request, pstate.header.stamp);
00096 }
00097
00098 throttle_request = clamp(0.0, throttle_request, 1.0);
00099 if (fabsf(throttle_request - throttle->value()) > Epsilon::throttle_position)
00100 {
00101 throttle->publish(throttle_request, pstate.header.stamp);
00102 }
00103 }
00104
00106 void AccelExample::reconfigure(art_pilot::PilotConfig &newconfig)
00107 {
00108 brake_pid_->Configure(newconfig.brake_kp,
00109 newconfig.brake_ki,
00110 newconfig.brake_kd);
00111 throttle_pid_->Configure(newconfig.throttle_kp,
00112 newconfig.throttle_ki,
00113 newconfig.throttle_kd);
00114 }
00115
00117 void AccelExample::reset(void)
00118 {
00119 brake_pid_->Clear();
00120 throttle_pid_->Clear();
00121 }
00122
00123 };