Public Member Functions | Static Public Member Functions | Public Attributes | Private Attributes | List of all members
mvsim::DynamicsAckermannDrivetrain::ControllerTwistFrontSteerPID Class Reference

#include <VehicleAckermann_Drivetrain.h>

Inheritance diagram for mvsim::DynamicsAckermannDrivetrain::ControllerTwistFrontSteerPID:
Inheritance graph
[legend]

Public Member Functions

virtual void control_step (const DynamicsAckermannDrivetrain::TControllerInput &ci, DynamicsAckermannDrivetrain::TControllerOutput &co)
 
 ControllerTwistFrontSteerPID (DynamicsAckermannDrivetrain &veh)
 
virtual void load_config (const rapidxml::xml_node< char > &node)
 
virtual bool setTwistCommand (const double vx, const double wz)
 
virtual void teleop_interface (const TeleopInput &in, TeleopOutput &out)
 
- Public Member Functions inherited from mvsim::ControllerBaseTempl< VEH_DYNAMICS >
virtual void clearLogs ()
 
virtual void control_step (const typename VEH_DYNAMICS::TControllerInput &ci, typename VEH_DYNAMICS::TControllerOutput &co)=0
 
 ControllerBaseTempl (VEH_DYNAMICS &veh)
 
virtual void newLogSession ()
 
virtual void setLogRecording (bool recording)
 
virtual ~ControllerBaseTempl ()
 

Static Public Member Functions

static const char * class_name ()
 

Public Attributes

double KD
 PID controller parameters. More...
 
double KI
 
double KP
 
double max_torque
 Maximum abs. value torque (for clamp) [Nm]. More...
 
double setpoint_ang_speed
 desired velocities (m/s) and (rad/s) More...
 
double setpoint_lin_speed
 

Private Attributes

double m_dist_fWheels
 
PID_Controller m_PID
 
double m_r2f_L
 

Additional Inherited Members

- Protected Attributes inherited from mvsim::ControllerBaseTempl< VEH_DYNAMICS >
VEH_DYNAMICS & m_veh
 

Detailed Description

PID controller that controls the vehicle with front traction & steering from Twist commands

Definition at line 111 of file VehicleAckermann_Drivetrain.h.

Constructor & Destructor Documentation

DynamicsAckermannDrivetrain::ControllerTwistFrontSteerPID::ControllerTwistFrontSteerPID ( DynamicsAckermannDrivetrain veh)

Member Function Documentation

static const char* mvsim::DynamicsAckermannDrivetrain::ControllerTwistFrontSteerPID::class_name ( )
inlinestatic

Directly set these values to tell the controller the desired setpoints

Definition at line 115 of file VehicleAckermann_Drivetrain.h.

void DynamicsAckermannDrivetrain::ControllerTwistFrontSteerPID::control_step ( const DynamicsAckermannDrivetrain::TControllerInput ci,
DynamicsAckermannDrivetrain::TControllerOutput co 
)
virtual
void DynamicsAckermannDrivetrain::ControllerTwistFrontSteerPID::load_config ( const rapidxml::xml_node< char > &  node)
virtual

Override to load class-specific options from the <controller> node

Reimplemented from mvsim::ControllerBaseTempl< VEH_DYNAMICS >.

Definition at line 64 of file Vehicleackermann_Drivetrain_ControllerTwistFrontSteerPID.cpp.

virtual bool mvsim::DynamicsAckermannDrivetrain::ControllerTwistFrontSteerPID::setTwistCommand ( const double  vx,
const double  wz 
)
inlinevirtual

Accept a Twist command.

Returns
true if the controller supports this kind of commands, false otherwise

Reimplemented from mvsim::ControllerBaseInterface.

Definition at line 130 of file VehicleAckermann_Drivetrain.h.

void DynamicsAckermannDrivetrain::ControllerTwistFrontSteerPID::teleop_interface ( const TeleopInput in,
TeleopOutput out 
)
virtual

This is to handle basic need of all the controllers.

Reimplemented from mvsim::ControllerBaseTempl< VEH_DYNAMICS >.

Definition at line 81 of file Vehicleackermann_Drivetrain_ControllerTwistFrontSteerPID.cpp.

Member Data Documentation

double mvsim::DynamicsAckermannDrivetrain::ControllerTwistFrontSteerPID::KD

PID controller parameters.

Definition at line 126 of file VehicleAckermann_Drivetrain.h.

double mvsim::DynamicsAckermannDrivetrain::ControllerTwistFrontSteerPID::KI

Definition at line 126 of file VehicleAckermann_Drivetrain.h.

double mvsim::DynamicsAckermannDrivetrain::ControllerTwistFrontSteerPID::KP

Definition at line 126 of file VehicleAckermann_Drivetrain.h.

double mvsim::DynamicsAckermannDrivetrain::ControllerTwistFrontSteerPID::m_dist_fWheels
private

Definition at line 138 of file VehicleAckermann_Drivetrain.h.

PID_Controller mvsim::DynamicsAckermannDrivetrain::ControllerTwistFrontSteerPID::m_PID
private

Definition at line 139 of file VehicleAckermann_Drivetrain.h.

double mvsim::DynamicsAckermannDrivetrain::ControllerTwistFrontSteerPID::m_r2f_L
private

Definition at line 138 of file VehicleAckermann_Drivetrain.h.

double mvsim::DynamicsAckermannDrivetrain::ControllerTwistFrontSteerPID::max_torque

Maximum abs. value torque (for clamp) [Nm].

Definition at line 127 of file VehicleAckermann_Drivetrain.h.

double mvsim::DynamicsAckermannDrivetrain::ControllerTwistFrontSteerPID::setpoint_ang_speed

desired velocities (m/s) and (rad/s)

Definition at line 118 of file VehicleAckermann_Drivetrain.h.

double mvsim::DynamicsAckermannDrivetrain::ControllerTwistFrontSteerPID::setpoint_lin_speed

Definition at line 118 of file VehicleAckermann_Drivetrain.h.


The documentation for this class was generated from the following files:


mvsim
Author(s):
autogenerated on Thu Jun 6 2019 19:36:41