15 #include <mrpt/opengl/CSetOfObjects.h>    16 #include <mrpt/math/lightweight_geom_data.h>    17 #if MRPT_VERSION<0x199    18 #include <mrpt/utils/TColor.h>    19 using mrpt::utils::TColor;
    20 using mrpt::utils::keep_min;
    21 using mrpt::utils::keep_max;
    22 using mrpt::utils::signWithZero;
    24 #include <mrpt/img/TColor.h>    25 using mrpt::img::TColor;
    28 using mrpt::signWithZero;
    99                 virtual void control_step(
   103                 virtual void load_config(
   105                 virtual void teleop_interface(
   115                 static const char* 
class_name() { 
return "twist_front_steer_pid"; }
   120                 virtual void control_step(
   132                         setpoint_lin_speed = vx;
   133                         setpoint_ang_speed = wz;
   146                 static const char* 
class_name() { 
return "front_steer_pid"; }
   150                 virtual void control_step(
   156                 virtual void load_config(
   158                 virtual void teleop_interface(
   185                 const double desired_equiv_steer_ang, 
double& out_fl_ang,
   186                 double& out_fr_ang) 
const;
   191                 const double w1, 
const double w2, 
const double diffBias,
   192                 const double defaultSplitRatio, 
double& t1, 
double& t2);
 
ControllerBasePtr & getController()
DifferentialType m_diff_type
min turning radius 
double setpoint_lin_speed
double max_torque
Maximum abs. value torque (for clamp) [Nm]. 
void setMaxSteeringAngle(double val)
static const char * class_name()
double setpoint_steer_ang
DynamicsAckermannDrivetrain(World *parent)
double getMaxSteeringAngle() const 
ControllerBaseTempl< DynamicsAckermannDrivetrain > ControllerBase
ControllerTwistFrontSteerPID m_twist_control
void computeDiffTorqueSplit(const double w1, const double w2, const double diffBias, const double defaultSplitRatio, double &t1, double &t2)
const ControllerBasePtr & getController() const 
virtual ControllerBaseInterface * getControllerInterface()
static const char * class_name()
static const char * class_name()
#define DECLARES_REGISTER_VEHICLE_DYNAMICS(CLASS_NAME)
virtual void invoke_motor_controllers(const TSimulContext &context, std::vector< double > &out_force_per_wheel)
std::shared_ptr< ControllerBase > ControllerBasePtr
double steer_ang
Equivalent ackerman steering angle. 
ControllerBasePtr m_controller
The installed controller. 
virtual bool setTwistCommand(const double vx, const double wz)
virtual void dynamics_load_params_from_xml(const rapidxml::xml_node< char > *xml_node)
double max_torque
Maximum abs. value torque (for clamp) [Nm]. 
virtual vec3 getVelocityLocalOdoEstimate() const 
double setpoint_wheel_torque
void computeFrontWheelAngles(const double desired_equiv_steer_ang, double &out_fl_ang, double &out_fr_ang) const