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::DEG2RAD;
21 using mrpt::utils::keep_min;
22 using mrpt::utils::keep_max;
24 #include <mrpt/img/TColor.h> 25 using mrpt::img::TColor;
88 virtual void control_step(
91 virtual void load_config(
93 virtual void teleop_interface(
103 static const char*
class_name() {
return "twist_front_steer_pid"; }
108 virtual void control_step(
111 virtual void load_config(
113 virtual void teleop_interface(
122 setpoint_lin_speed = vx;
123 setpoint_ang_speed = wz;
138 static const char*
class_name() {
return "front_steer_pid"; }
142 virtual void control_step(
147 virtual void load_config(
149 virtual void teleop_interface(
176 const double desired_equiv_steer_ang,
double& out_fl_ang,
177 double& out_fr_ang)
const;
virtual ControllerBaseInterface * getControllerInterface()
double setpoint_wheel_torque_r
DynamicsAckermann(World *parent)
double max_torque
Maximum abs. value torque (for clamp) [Nm].
ControllerBasePtr m_controller
The installed controller.
const ControllerBasePtr & getController() const
void setMaxSteeringAngle(double val)
ControllerBaseTempl< DynamicsAckermann > ControllerBase
virtual void dynamics_load_params_from_xml(const rapidxml::xml_node< char > *xml_node)
virtual vec3 getVelocityLocalOdoEstimate() const
double setpoint_lin_speed
#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.
virtual bool setTwistCommand(const double vx, const double wz)
double getMaxSteeringAngle() const
double max_torque
Maximum abs. value torque (for clamp) [Nm].
static const char * class_name()
virtual void invoke_motor_controllers(const TSimulContext &context, std::vector< double > &out_force_per_wheel)
ControllerTwistFrontSteerPID m_twist_control
static const char * class_name()
static const char * class_name()