Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010 #pragma once
00011
00012 #include <mvsim/VehicleBase.h>
00013 #include <mvsim/PID_Controller.h>
00014
00015 #include <mrpt/math/lightweight_geom_data.h>
00016
00017 namespace mvsim
00018 {
00022 class DynamicsDifferential : public VehicleBase
00023 {
00024 DECLARES_REGISTER_VEHICLE_DYNAMICS(DynamicsDifferential)
00025 public:
00026 enum
00027 {
00028 WHEEL_L = 0,
00029 WHEEL_R = 1
00030 };
00031
00032 DynamicsDifferential(World* parent);
00033
00037 struct TControllerInput
00038 {
00039 TSimulContext context;
00040 };
00041 struct TControllerOutput
00042 {
00043 double wheel_torque_l, wheel_torque_r;
00044 TControllerOutput() : wheel_torque_l(0), wheel_torque_r(0) {}
00045 };
00046
00048 typedef ControllerBaseTempl<DynamicsDifferential> ControllerBase;
00049 typedef std::shared_ptr<ControllerBase> ControllerBasePtr;
00050
00051 class ControllerRawForces : public ControllerBase
00052 {
00053 public:
00054 ControllerRawForces(DynamicsDifferential& veh)
00055 : ControllerBase(veh),
00056 setpoint_wheel_torque_l(0),
00057 setpoint_wheel_torque_r(0)
00058 {
00059 }
00060 static const char* class_name() { return "raw"; }
00063 double setpoint_wheel_torque_l, setpoint_wheel_torque_r;
00064 virtual void control_step(
00065 const DynamicsDifferential::TControllerInput& ci,
00066 DynamicsDifferential::TControllerOutput&
00067 co);
00068 virtual void teleop_interface(
00069 const TeleopInput& in, TeleopOutput& out);
00070 };
00071
00074 class ControllerTwistPID : public ControllerBase
00075 {
00076 public:
00077 ControllerTwistPID(DynamicsDifferential& veh);
00078 static const char* class_name() { return "twist_pid"; }
00081 double setpoint_lin_speed,
00082 setpoint_ang_speed;
00083 virtual void control_step(
00084 const DynamicsDifferential::TControllerInput& ci,
00085 DynamicsDifferential::TControllerOutput&
00086 co);
00087 virtual void load_config(
00088 const rapidxml::xml_node<char>& node);
00089 virtual void teleop_interface(
00090 const TeleopInput& in, TeleopOutput& out);
00091
00092 double KP, KI, KD;
00093 double max_torque;
00094
00095 virtual bool setTwistCommand(const double vx, const double wz)
00096 {
00097 setpoint_lin_speed = vx;
00098 setpoint_ang_speed = wz;
00099 return true;
00100 }
00101
00102 private:
00103 double m_distWheels;
00104 PID_Controller m_PID[2];
00105 };
00106
00107 const ControllerBasePtr& getController() const { return m_controller; }
00108 ControllerBasePtr& getController() { return m_controller; }
00109 virtual ControllerBaseInterface* getControllerInterface()
00110 {
00111 return m_controller.get();
00112 }
00113
00115
00116 virtual vec3 getVelocityLocalOdoEstimate() const;
00117
00118 protected:
00119
00120 virtual void dynamics_load_params_from_xml(
00121 const rapidxml::xml_node<char>* xml_node);
00122
00123 virtual void invoke_motor_controllers(
00124 const TSimulContext& context, std::vector<double>& out_force_per_wheel);
00125
00126 private:
00127 ControllerBasePtr m_controller;
00128 };
00129 }