diff --git a/robots/gimbalrotor/include/gimbalrotor/gimbalrotor_navigation.h b/robots/gimbalrotor/include/gimbalrotor/gimbalrotor_navigation.h index 97c0494a6..3d26c066c 100644 --- a/robots/gimbalrotor/include/gimbalrotor/gimbalrotor_navigation.h +++ b/robots/gimbalrotor/include/gimbalrotor/gimbalrotor_navigation.h @@ -15,7 +15,8 @@ namespace aerial_robot_navigation void initialize(ros::NodeHandle nh, ros::NodeHandle nhp, boost::shared_ptr robot_model, - boost::shared_ptr estimator) override; + boost::shared_ptr estimator, + double loop_du) override; void update() override; diff --git a/robots/gimbalrotor/src/gimbalrotor_navigation.cpp b/robots/gimbalrotor/src/gimbalrotor_navigation.cpp index a1c648dd4..f49898591 100644 --- a/robots/gimbalrotor/src/gimbalrotor_navigation.cpp +++ b/robots/gimbalrotor/src/gimbalrotor_navigation.cpp @@ -14,10 +14,11 @@ GimbalrotorNavigator::GimbalrotorNavigator(): void GimbalrotorNavigator::initialize(ros::NodeHandle nh, ros::NodeHandle nhp, boost::shared_ptr robot_model, - boost::shared_ptr estimator) + boost::shared_ptr estimator, + double loop_du) { /* initialize the flight control */ - BaseNavigator::initialize(nh, nhp, robot_model, estimator); + BaseNavigator::initialize(nh, nhp, robot_model, estimator, loop_du); curr_target_baselink_rot_pub_ = nh_.advertise("desire_coordinate", 1); final_target_baselink_rot_sub_ = nh_.subscribe("final_target_baselink_rot", 1, &GimbalrotorNavigator::setFinalTargetBaselinkRotCallback, this);