Skip to content

Commit ee302e6

Browse files
committed
A small bug patch for takeoff
1 parent b198c00 commit ee302e6

1 file changed

Lines changed: 4 additions & 2 deletions

File tree

src/move/src/handler.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -28,10 +28,10 @@ bool Drone::takeoff(float z){
2828
return false;
2929
}
3030
else{
31+
flying_status = true;
3132
moveRelative({0,0,z,true});
3233
// Here may need to sleep a while, then control if movement is done or still running.
3334
// But for now I do not write such a thing
34-
flying_status = true;
3535
return true;
3636
}
3737
}
@@ -214,8 +214,10 @@ int main(int argc, char **argv){
214214
ros::init(argc, argv, "handler");
215215
ros::NodeHandle nh;
216216
ros::Rate rate(0.2);
217+
Drone drone = Drone(nh);
218+
drone.takeoff(5);
217219
while(ros::ok()){
218-
position pos = {0,0,2,false};
220+
position pos = {0,0,5,false};
219221
rate.sleep();
220222
}
221223
}

0 commit comments

Comments
 (0)