12 #include <mrpt/img/TColor.h> 72 virtual void control_step(
76 virtual void teleop_interface(
86 static const char*
class_name() {
return "twist_front_steer_pid"; }
91 virtual void control_step(
95 virtual void teleop_interface(
104 setpoint_lin_speed = t.vx;
105 setpoint_ang_speed = t.omega;
120 static const char*
class_name() {
return "front_steer_pid"; }
124 virtual void control_step(
130 virtual void teleop_interface(
157 const double desired_equiv_steer_ang,
double& out_fl_ang,
158 double& out_fr_ang)
const;
double setpoint_wheel_torque_r
ControllerBase::Ptr & getController()
virtual std::vector< double > invoke_motor_controllers(const TSimulContext &context) override
DynamicsAckermann(World *parent)
double max_torque
Maximum abs. value torque (for clamp) [Nm].
virtual mrpt::math::TTwist2D getVelocityLocalOdoEstimate() const override
ControllerBase::Ptr controller_
The installed controller.
void computeFrontWheelAngles(const double desired_equiv_steer_ang, double &out_fl_ang, double &out_fr_ang) const
virtual void dynamics_load_params_from_xml(const rapidxml::xml_node< char > *xml_node) override
void setMaxSteeringAngle(double val)
double getMaxSteeringAngle() const
std::shared_ptr< ControllerBaseTempl< VEH_DYNAMICS > > Ptr
double setpoint_lin_speed
#define DECLARES_REGISTER_VEHICLE_DYNAMICS(CLASS_NAME)
double setpoint_steer_ang
virtual bool setTwistCommand(const mrpt::math::TTwist2D &t) override
const ControllerBase::Ptr & getController() const
double steer_ang
Equivalent Ackermann steering angle.
double max_torque
Maximum abs. value torque (for clamp) [Nm].
static const char * class_name()
static const char * class_name()
ControllerTwistFrontSteerPID twist_control_
static const char * class_name()
virtual ControllerBaseInterface * getControllerInterface() override