14 using namespace mvsim;
20 setpoint_lin_speed(0),
21 setpoint_ang_speed(0),
58 const std::vector<mrpt::math::TVector2D> desired_wheel_vels =
59 veh_.getWheelsVelocityLocal(
62 ASSERT_(desired_wheel_vels.size() == 4);
66 double vel_fl, vel_fr;
67 double desired_fl_steer_ang, desired_fr_steer_ang;
68 veh_.computeFrontWheelAngles(
69 co.
steer_ang, desired_fl_steer_ang, desired_fr_steer_ang);
71 const mrpt::poses::CPose2D wRotInv(0, 0, -desired_fl_steer_ang);
72 mrpt::math::TPoint2D vel_w;
78 const mrpt::poses::CPose2D wRotInv(0, 0, -desired_fr_steer_ang);
79 mrpt::math::TPoint2D vel_w;
87 double act_vel_fl, act_vel_fr;
90 const std::vector<mrpt::math::TVector2D> odo_wheel_vels =
91 veh_.getWheelsVelocityLocal(
veh_.getVelocityLocalOdoEstimate());
92 ASSERT_(odo_wheel_vels.size() == 4);
94 const double actual_fl_steer_ang =
96 const double actual_fr_steer_ang =
100 const mrpt::poses::CPose2D wRotInv(0, 0, -actual_fl_steer_ang);
101 mrpt::math::TPoint2D vel_w;
102 wRotInv.composePoint(
104 act_vel_fl = vel_w.x;
107 const mrpt::poses::CPose2D wRotInv(0, 0, -actual_fr_steer_ang);
108 mrpt::math::TPoint2D vel_w;
109 wRotInv.composePoint(
111 act_vel_fr = vel_w.x;
116 for (
int i = 0; i < 2; i++)
181 "] Teleop keys: w/s=incr/decr lin speed. " 182 "a/d=left/right steering. spacebar=stop.\n";
virtual void control_step(const DynamicsAckermann::TControllerInput &ci, DynamicsAckermann::TControllerOutput &co) override
std::map< std::string, TParamEntry > TParameterDefinitions
void parse_xmlnode_children_as_param(const rapidxml::xml_node< char > &xml_node, const TParameterDefinitions ¶ms, const std::map< std::string, std::string > &variableNamesValues={}, const char *functionNameContext="", mrpt::system::COutputLogger *logger=nullptr)
double max_torque
Maximum abs. value torque (for clamp) [Nm].
double setpoint_ang_speed
desired velocities (m/s) and (rad/s)
double KD
PID controller parameters.
virtual void teleop_interface(const TeleopInput &in, TeleopOutput &out) override
INLINE Rall1d< T, V, S > atan(const Rall1d< T, V, S > &x)
double setpoint_lin_speed
virtual void teleop_interface(const TeleopInput &in, TeleopOutput &out) override
virtual void load_config(const rapidxml::xml_node< char > &node) override
double max_out
For clamping (0=no clamp)
double compute(double err, double dt)
double steer_ang
Equivalent Ackermann steering angle.
std::string append_gui_lines
static const char * class_name()
ControllerTwistFrontSteerPID(DynamicsAckermann &veh)