12 #include <mrpt/img/TColor.h> 84 virtual void control_step(
88 virtual void teleop_interface(
98 static const char*
class_name() {
return "twist_front_steer_pid"; }
103 virtual void control_step(
107 virtual void teleop_interface(
116 setpoint_lin_speed = vx;
117 setpoint_ang_speed = wz;
130 static const char*
class_name() {
return "front_steer_pid"; }
134 virtual void control_step(
140 virtual void teleop_interface(
167 const double desired_equiv_steer_ang,
double& out_fl_ang,
168 double& out_fr_ang)
const;
173 const double w1,
const double w2,
const double diffBias,
174 const double defaultSplitRatio,
double& t1,
double& t2);
183 std::vector<double>& out_force_per_wheel)
override;
ControllerBasePtr & getController()
DifferentialType m_diff_type
min turning radius
double setpoint_lin_speed
virtual mrpt::math::TTwist2D getVelocityLocalOdoEstimate() const override
double max_torque
Maximum abs. value torque (for clamp) [Nm].
void setMaxSteeringAngle(double val)
static const char * class_name()
double setpoint_steer_ang
virtual void dynamics_load_params_from_xml(const rapidxml::xml_node< char > *xml_node) override
virtual void invoke_motor_controllers(const TSimulContext &context, std::vector< double > &out_force_per_wheel) override
virtual ControllerBaseInterface * getControllerInterface() override
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
static const char * class_name()
static const char * class_name()
#define DECLARES_REGISTER_VEHICLE_DYNAMICS(CLASS_NAME)
GLdouble GLdouble GLint GLint GLdouble GLdouble GLint GLint GLdouble GLdouble w2
std::shared_ptr< ControllerBase > ControllerBasePtr
double steer_ang
Equivalent ackerman steering angle.
virtual bool setTwistCommand(const double vx, const double wz) override
ControllerBasePtr m_controller
The installed controller.
double max_torque
Maximum abs. value torque (for clamp) [Nm].
double setpoint_wheel_torque
void computeFrontWheelAngles(const double desired_equiv_steer_ang, double &out_fl_ang, double &out_fr_ang) const
GLdouble GLdouble GLint GLint GLdouble GLdouble GLint GLint GLdouble w1