12 #include <mrpt/img/TColor.h>    73                 virtual void control_step(
    77                 virtual void teleop_interface(
    87                 static const char* 
class_name() { 
return "twist_front_steer_pid"; }
    92                 virtual void control_step(
    96                 virtual void teleop_interface(
   105                         setpoint_lin_speed = vx;
   106                         setpoint_ang_speed = wz;
   121                 static const char* 
class_name() { 
return "front_steer_pid"; }
   125                 virtual void control_step(
   131                 virtual void teleop_interface(
   158                 const double desired_equiv_steer_ang, 
double& out_fl_ang,
   159                 double& out_fr_ang) 
const;
   168                 std::vector<double>& out_force_per_wheel) 
override;
 
double setpoint_wheel_torque_r
virtual void invoke_motor_controllers(const TSimulContext &context, std::vector< double > &out_force_per_wheel) override
DynamicsAckermann(World *parent)
double max_torque
Maximum abs. value torque (for clamp) [Nm]. 
ControllerBasePtr m_controller
The installed controller. 
virtual mrpt::math::TTwist2D getVelocityLocalOdoEstimate() const override
const ControllerBasePtr & getController() const 
virtual void dynamics_load_params_from_xml(const rapidxml::xml_node< char > *xml_node) override
void setMaxSteeringAngle(double val)
ControllerBaseTempl< DynamicsAckermann > ControllerBase
double setpoint_lin_speed
virtual bool setTwistCommand(const double vx, const double wz) override
#define DECLARES_REGISTER_VEHICLE_DYNAMICS(CLASS_NAME)
void computeFrontWheelAngles(const double desired_equiv_steer_ang, double &out_fl_ang, double &out_fr_ang) const 
ControllerBasePtr & getController()
double setpoint_steer_ang
std::shared_ptr< ControllerBase > ControllerBasePtr
double steer_ang
Equivalent ackerman steering angle. 
double getMaxSteeringAngle() const 
double max_torque
Maximum abs. value torque (for clamp) [Nm]. 
static const char * class_name()
ControllerTwistFrontSteerPID m_twist_control
static const char * class_name()
static const char * class_name()
virtual ControllerBaseInterface * getControllerInterface() override