17 using namespace mvsim;
24 if (node && 0 != strcmp(node->
name(),
"friction"))
25 throw std::runtime_error(
26 "<friction>...</friction> XML node was expected!!");
31 std::map<std::string, TParamEntry> params;
43 mrpt::math::TPoint2D& out_result_force_local)
const 46 const mrpt::poses::CPose2D wRot(0, 0, input.
wheel.
yaw);
47 const mrpt::poses::CPose2D wRotInv(0, 0, -input.
wheel.
yaw);
48 mrpt::math::TPoint2D vel_w;
53 const double mu =
m_mu;
56 const double max_friction = mu * partial_mass * gravity;
60 double wheel_lat_friction = 0.0;
63 wheel_lat_friction = -vel_w.y * partial_mass / input.
context.
dt;
66 b2Clamp(wheel_lat_friction, -max_friction, max_friction);
71 double wheel_long_friction = 0.0;
79 const double lon_constraint_desired_wheel_w = vel_w.x / R;
80 const double desired_wheel_w_impulse =
81 (lon_constraint_desired_wheel_w - input.
wheel.
getW());
82 const double desired_wheel_alpha =
83 desired_wheel_w_impulse / input.
context.
dt;
93 double F_friction_lon = (input.
motor_torque - I_yy * desired_wheel_alpha -
98 F_friction_lon =
b2Clamp(F_friction_lon, -max_friction, max_friction);
101 const double actual_wheel_alpha = (input.
motor_torque - R * F_friction_lon -
109 wheel_long_friction = F_friction_lon;
113 const mrpt::math::TPoint2D result_force_wrt_wheel(
114 wheel_long_friction, wheel_lat_friction);
117 wRot.composePoint(result_force_wrt_wheel, out_result_force_local);
This file contains rapidxml parser and DOM implementation.
void setW(double val)
Spinning velocity (rad/s) wrt shaft.
DefaultFriction(VehicleBase &my_vehicle, const rapidxml::xml_node< char > *node)
double m_mu
friction coeficient (non-dimensional)
double get_gravity() const
void parse_xmlnode_children_as_param(const rapidxml::xml_node< char > &xml_node, const std::map< std::string, TParamEntry > ¶ms, const char *function_name_context="")
double getW() const
Spinning velocity (rad/s) wrt shaft.
double diameter
[m,rad] (in local coords)
T b2Clamp(T a, T low, T high)
VehicleBase & m_my_vehicle
virtual void evaluate_friction(const FrictionBase::TFrictionInput &input, mrpt::math::TPoint2D &out_result_force_local) const
double m_C_damping
For wheels "internal friction" (N*m*s/rad)