|
@@ -40,7 +40,7 @@ void ConfigHandler::loadConfig() {
|
|
main_timer_frequency_ =
|
|
main_timer_frequency_ =
|
|
declareOrGetParam<float>(node_, "main_timer_frequency", 50.0);
|
|
declareOrGetParam<float>(node_, "main_timer_frequency", 50.0);
|
|
imu_timer_frequency_ =
|
|
imu_timer_frequency_ =
|
|
- declareOrGetParam<float>(node_, "imu_timer_frequency", 30.0);
|
|
|
|
|
|
+ declareOrGetParam<float>(node_, "imu_timer_frequency", 200.0);
|
|
legged_odom_timer_frequency_ =
|
|
legged_odom_timer_frequency_ =
|
|
declareOrGetParam<float>(node_, "legged_odom_timer_frequency", 100.0);
|
|
declareOrGetParam<float>(node_, "legged_odom_timer_frequency", 100.0);
|
|
joints_state_timer_frequency_ =
|
|
joints_state_timer_frequency_ =
|