$search
00001 /* -*- mode: C++ -*- 00002 * 00003 * Copyright (C) 2011 Austin Robot Technology 00004 * License: Modified BSD Software License Agreement 00005 * 00006 * $Id: accel_plan.h 1539 2011-05-09 04:09:20Z jack.oquin $ 00007 */ 00008 00017 #ifndef _ACCEL_PLAN_H_ 00018 #define _ACCEL_PLAN_H_ 00019 00020 #include "accel.h" 00021 00022 class Pid; // class reference for pointers 00023 00024 namespace pilot 00025 { 00026 00028 class AccelPlan: public AccelBase 00029 { 00030 public: 00031 00032 AccelPlan(art_pilot::PilotConfig &config); 00033 virtual ~AccelPlan(); 00034 00035 typedef boost::shared_ptr<device_interface::ServoDeviceBase> ServoPtr; 00036 00043 virtual void adjust(art_msgs::PilotState &pstate, 00044 ServoPtr brake, ServoPtr throttle); 00045 00047 virtual void reconfigure(art_pilot::PilotConfig &newconfig); 00048 00050 virtual void reset(void); 00051 00052 private: 00053 00062 void adjustVelocity(art_msgs::PilotState &pstate, 00063 ServoPtr brake, ServoPtr throttle); 00064 00065 float speed_; // absolute value of target velocity 00066 float accel_; // absolute value of acceleration 00067 ros::Time prev_cycle_; // previous cycle time for this plan 00068 00069 // When true, brake is the controlling device, otherwise throttle. 00070 bool braking_; 00071 00072 boost::shared_ptr<Pid> brake_pid_; // Brake_Pilot control PID 00073 boost::shared_ptr<Pid> throttle_pid_; // Throttle control PID 00074 }; 00075 00076 }; // namespace pilot 00077 00078 #endif // _ACCEL_PLAN_H_