diff --git a/src/keyboard_ctl.cpp b/src/keyboard_ctl.cpp index ef8f643..5d38d5b 100644 --- a/src/keyboard_ctl.cpp +++ b/src/keyboard_ctl.cpp @@ -141,9 +141,11 @@ int main(int argc, char **argv) nh.getParam("velocity_horizon", h_speed); nh.getParam("velocity_vertical", v_speed); nh.getParam("angular_velocity_turn", turn_speed); + nh.getParam("update_rate", update_rate); cout << "horizon speed: " << h_speed << endl; cout << "vertical speed: " << v_speed << endl; cout << "turning speed: " << turn_speed << endl; + cout << "update rate: " << update_rate << endl; ros::Subscriber state_sub = nh.subscribe ("/mavros/state", 10, state_cb);