Autonomous Racing  1
f1tenth Project Group of Technical University Dortmund, Germany
params_to_yaml.cpp
Go to the documentation of this file.
1 #include "car_config.h"
2 #include "yaml-cpp/yaml.h"
3 #include <fstream>
4 #include <ros/package.h>
5 
6 int main(int argc, char** argv)
7 {
8  YAML::Node node;
9  node["speed_to_erpm_gain"] = car_config::SPEED_TO_ERPM;
10  node["speed_to_erpm_offset"] = 0;
11  node["steering_angle_to_servo_gain"] = car_config::STEERING_TO_SERVO_GAIN;
12  node["steering_angle_to_servo_offset"] = car_config::STEERING_TO_SERVO_OFFSET;
13  node["wheelbase"] = car_config::WHEELBASE;
14 
15  std::string package_path = ros::package::getPath("vesc_sim");
16  std::ofstream fout(package_path + "/config/car_config.yaml");
17  fout << node;
18 }
node
Definition: train.py:99
constexpr double SPEED_TO_ERPM
Conversion factor from meters per second to electrical revolutions per minute s/ (m * minute) = 1/m...
Definition: car_config.h:56
constexpr double WHEELBASE
The distance between the front and rear axes.
Definition: car_config.h:15
constexpr double STEERING_TO_SERVO_GAIN
Conversion factor from steering angle to servo input 1/radian.
Definition: car_config.h:73
int main(int argc, char **argv)
constexpr double STEERING_TO_SERVO_OFFSET
Position of the servo for normal wheel position.
Definition: car_config.h:67