15 #include <mrpt/opengl/COpenGLScene.h>    18 using namespace mvsim;
    27         m_chassis_mass = 15.0;
    28         m_chassis_z_min = 0.05;
    29         m_chassis_z_max = 0.6;
    30         m_chassis_color = TColor(0xff, 0x00, 0x00);
    33         m_chassis_poly.clear();
    34         m_chassis_poly.push_back(TPoint2D(-0.4, -0.5));
    35         m_chassis_poly.push_back(TPoint2D(-0.4, 0.5));
    36         m_chassis_poly.push_back(TPoint2D(0.4, 0.5));
    37         m_chassis_poly.push_back(TPoint2D(0.6, 0.3));
    38         m_chassis_poly.push_back(TPoint2D(0.6, -0.3));
    39         m_chassis_poly.push_back(TPoint2D(0.4, -0.5));
    40         updateMaxRadiusFromPoly();
    42         m_fixture_chassis = NULL;
    43         for (
int i = 0; i < 2; i++) m_fixture_wheels[i] = NULL;
    56                 std::map<std::string, TParamEntry> attribs;
    57                 attribs[
"mass"] = 
TParamEntry(
"%lf", &this->m_chassis_mass);
    58                 attribs[
"zmin"] = 
TParamEntry(
"%lf", &this->m_chassis_z_min);
    59                 attribs[
"zmax"] = 
TParamEntry(
"%lf", &this->m_chassis_z_max);
    60                 attribs[
"color"] = 
TParamEntry(
"%color", &this->m_chassis_color);
    63                         *xml_chassis, attribs,
    64                         "[DynamicsDifferential::dynamics_load_params_from_xml]");
    71                                 *xml_shape, m_chassis_poly,
    72                                 "[DynamicsDifferential::dynamics_load_params_from_xml]");
    76         const char* w_names[2] = {
"l_wheel", 
"r_wheel"};
    77         const double w_default_y[2] = {0.5, -0.5};
    79         for (
size_t i = 0; i < 2; i++)
    84                         m_wheels_info[i].loadFromXML(xml_wheel);
    87                         m_wheels_info[i] = 
Wheel();
    88                         m_wheels_info[i].y = w_default_y[i];
   101                         if (!control_class || !control_class->
value())
   103                                         "[DynamicsDifferential] Missing 'class' attribute in "   104                                         "<controller> XML node");
   106                         const std::string sCtrlClass = std::string(control_class->
value());
   115                                                 "[DynamicsDifferential] Unknown 'class'='%s' in "   116                                                 "<controller> XML node",
   117                                                 sCtrlClass.c_str()));
   130         const TSimulContext& context, std::vector<double>& out_torque_per_wheel)
   133         out_torque_per_wheel.assign(2, 0.0);
   157         const double w0 = m_wheels_info[
WHEEL_L].getW();
   158         const double w1 = m_wheels_info[
WHEEL_R].getW();
   159         const double R0 = m_wheels_info[
WHEEL_L].diameter * 0.5;
   160         const double R1 = m_wheels_info[
WHEEL_R].diameter * 0.5;
   162         const double Ay = m_wheels_info[
WHEEL_L].y - m_wheels_info[
WHEEL_R].y;
   165                 "The two wheels of a differential vehicle CAN'T by at the same Y "   168         const double w_veh = (w1 * R1 - w0 * R0) / Ay;
   169         const double vx_veh = w0 * R0 + w_veh * m_wheels_info[
WHEEL_L].y;
   171         odo_vel.
vals[0] = vx_veh;
   172         odo_vel.
vals[2] = w_veh;
   175         odo_vel.
vals[1] = 0.0;
   180                 printf(
"\n gt: vx=%7.03f, vy=%7.03f, w= %7.03fdeg\n", gt_vel.
vals[0], gt_vel.
vals[1], mrpt::utils::RAD2DEG(gt_vel.
vals[2]));
   181                 printf(
"odo: vx=%7.03f, vy=%7.03f, w= %7.03fdeg\n", odo_vel.
vals[0], odo_vel.
vals[1], mrpt::utils::RAD2DEG(odo_vel.
vals[2]));
 
This file contains rapidxml parser and DOM implementation. 
void parse_xmlnode_shape(const rapidxml::xml_node< char > &xml_node, mrpt::math::TPolygon2D &out_poly, const char *function_name_context="")
virtual void invoke_motor_controllers(const TSimulContext &context, std::vector< double > &out_force_per_wheel)
DynamicsDifferential(World *parent)
xml_node< Ch > * first_node(const Ch *name=0, std::size_t name_size=0, bool case_sensitive=true) const 
static const char * class_name()
void parse_xmlnode_attribs(const rapidxml::xml_node< char > &xml_node, const std::map< std::string, TParamEntry > ¶ms, const char *function_name_context="")
virtual vec3 getVelocityLocalOdoEstimate() const 
std::shared_ptr< ControllerBase > ControllerBasePtr
virtual void dynamics_load_params_from_xml(const rapidxml::xml_node< char > *xml_node)
xml_attribute< Ch > * first_attribute(const Ch *name=0, std::size_t name_size=0, bool case_sensitive=true) const 
ControllerBasePtr m_controller
The installed controller. 
static const char * class_name()
vec3 getVelocityLocal() const