#include <VehicleAckermann.h>
Classes | |
class | ControllerFrontSteerPID |
class | ControllerRawForces |
class | ControllerTwistFrontSteerPID |
struct | TControllerInput |
struct | TControllerOutput |
Public Types | |
enum | { WHEEL_RL = 0, WHEEL_RR = 1, WHEEL_FL = 2, WHEEL_FR = 3 } |
Public Member Functions | |
void | computeFrontWheelAngles (const double desired_equiv_steer_ang, double &out_fl_ang, double &out_fr_ang) const |
DynamicsAckermann (World *parent) | |
double | getMaxSteeringAngle () const |
virtual vec3 | getVelocityLocalOdoEstimate () const |
void | setMaxSteeringAngle (double val) |
Protected Member Functions | |
virtual void | dynamics_load_params_from_xml (const rapidxml::xml_node< char > *xml_node) |
virtual void | invoke_motor_controllers (const TSimulContext &context, std::vector< double > &out_force_per_wheel) |
Private Attributes | |
ControllerBasePtr | m_controller |
The installed controller. | |
double | m_max_steer_ang |
Controllers | |
typedef ControllerBaseTempl < DynamicsAckermann > | ControllerBase |
typedef std::shared_ptr < ControllerBase > | ControllerBasePtr |
const ControllerBasePtr & | getController () const |
ControllerBasePtr & | getController () |
virtual ControllerBaseInterface * | getControllerInterface () |
Implementation of 4 wheels Ackermann-driven vehicles.
Definition at line 36 of file VehicleAckermann.h.
Virtual base for controllers of vehicles of type DynamicsAckermann
Definition at line 76 of file VehicleAckermann.h.
typedef std::shared_ptr<ControllerBase> mvsim::DynamicsAckermann::ControllerBasePtr |
Definition at line 77 of file VehicleAckermann.h.
anonymous enum |
Definition at line 41 of file VehicleAckermann.h.
DynamicsAckermann::DynamicsAckermann | ( | World * | parent | ) |
Definition at line 23 of file VehicleAckermann.cpp.
void DynamicsAckermann::computeFrontWheelAngles | ( | const double | desired_equiv_steer_ang, |
double & | out_fl_ang, | ||
double & | out_fr_ang | ||
) | const |
Computes the exact angles of the front wheels required to have an equivalent central steering angle. The method takes into account all wheels info & steering limits stored in the object.
Definition at line 202 of file VehicleAckermann.cpp.
void DynamicsAckermann::dynamics_load_params_from_xml | ( | const rapidxml::xml_node< char > * | xml_node | ) | [protected, virtual] |
The derived-class part of load_params_from_xml()
Implements mvsim::VehicleBase.
Definition at line 63 of file VehicleAckermann.cpp.
const ControllerBasePtr& mvsim::DynamicsAckermann::getController | ( | ) | const [inline] |
Definition at line 159 of file VehicleAckermann.h.
ControllerBasePtr& mvsim::DynamicsAckermann::getController | ( | ) | [inline] |
Definition at line 160 of file VehicleAckermann.h.
virtual ControllerBaseInterface* mvsim::DynamicsAckermann::getControllerInterface | ( | ) | [inline, virtual] |
Implements mvsim::VehicleBase.
Definition at line 161 of file VehicleAckermann.h.
double mvsim::DynamicsAckermann::getMaxSteeringAngle | ( | ) | const [inline] |
The maximum steering angle (rad). Determines min turning radius
Definition at line 52 of file VehicleAckermann.h.
vec3 DynamicsAckermann::getVelocityLocalOdoEstimate | ( | ) | const [virtual] |
Gets the current estimation of odometry-based velocity as reconstructed solely from wheels spinning velocities and geometry. This is the input of any realistic low-level controller onboard.
Implements mvsim::VehicleBase.
Definition at line 228 of file VehicleAckermann.cpp.
void DynamicsAckermann::invoke_motor_controllers | ( | const TSimulContext & | context, |
std::vector< double > & | out_force_per_wheel | ||
) | [protected, virtual] |
Implements mvsim::VehicleBase.
Definition at line 174 of file VehicleAckermann.cpp.
void mvsim::DynamicsAckermann::setMaxSteeringAngle | ( | double | val | ) | [inline] |
Definition at line 53 of file VehicleAckermann.h.
The installed controller.
Definition at line 188 of file VehicleAckermann.h.
double mvsim::DynamicsAckermann::m_max_steer_ang [private] |
The maximum steering angle (rad). Determines
Definition at line 190 of file VehicleAckermann.h.