$search
00001 /* 00002 * Copyright (C) 2011 Austin Robot Technology 00003 * License: Modified BSD Software License Agreement 00004 * 00005 * $Id: accel_speed.cc 1541 2011-05-09 19:07:23Z jack.oquin $ 00006 */ 00007 00016 #include <ros/ros.h> 00017 #include "accel_speed.h" 00018 00019 #include "speed.h" 00020 #include "learned_controller.h" 00021 00022 namespace pilot 00023 { 00024 00025 AccelSpeed::AccelSpeed(art_pilot::PilotConfig &config): 00026 AccelBase(config) 00027 { 00028 switch(config.acceleration_controller) 00029 { 00030 case art_pilot::Pilot_Speed_Learned: 00031 { 00032 ROS_INFO("using RL learned controller for speed control"); 00033 speed_.reset(new LearnedSpeedControl()); 00034 break; 00035 } 00036 case art_pilot::Pilot_Speed_Matrix: 00037 { 00038 ROS_INFO("using acceleration matrix for speed control"); 00039 speed_.reset(new SpeedControlMatrix()); 00040 break; 00041 } 00042 case art_pilot::Pilot_Speed_PID: 00043 { 00044 ROS_INFO("using brake and throttle PID for speed control"); 00045 speed_.reset(new SpeedControlPID()); 00046 break; 00047 } 00048 } 00049 00050 // pass configuration parameters to the relevant speed controller 00051 speed_->configure(config); 00052 }; 00053 00054 AccelSpeed::~AccelSpeed() {}; 00055 00056 void AccelSpeed::adjust(art_msgs::PilotState &pstate, 00057 ServoPtr brake, ServoPtr throttle) 00058 { 00059 // initialize interface to old SpeedControl class 00060 // 00061 // abs_speed: absolute value of current velocity in m/s 00062 // error: difference between that and our immediate goal 00063 // 00064 float abs_speed = fabs(pstate.current.speed); 00065 float error = fabs(pstate.target.speed) - abs_speed; 00066 float brake_request = brake->last_request(); 00067 float throttle_request = throttle->last_request(); 00068 speed_->set_brake_position(brake->value()); 00069 speed_->set_throttle_position(throttle->value()); 00070 00071 // Adjust brake and throttle settings. 00072 speed_->adjust(abs_speed, error, 00073 &brake_request, &throttle_request); 00074 00075 brake_request = clamp(0.0, brake_request, 1.0); 00076 if (fabsf(brake_request - brake->value()) > EPSILON_BRAKE) 00077 { 00078 brake->publish(brake_request, pstate.header.stamp); 00079 } 00080 00081 throttle_request = clamp(0.0, throttle_request, 1.0); 00082 if (fabsf(throttle_request - throttle->value()) > EPSILON_THROTTLE) 00083 { 00084 throttle->publish(throttle_request, pstate.header.stamp); 00085 } 00086 } 00087 00089 void AccelSpeed::reconfigure(art_pilot::PilotConfig &newconfig) 00090 { 00091 // pass new configuration to underlying speed control class 00092 speed_->configure(newconfig); 00093 } 00094 00096 void AccelSpeed::reset(void) 00097 { 00098 speed_->reset(); 00099 } 00100 00101 };