We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
1 parent b198c00 commit ee302e6Copy full SHA for ee302e6
1 file changed
src/move/src/handler.cpp
@@ -28,10 +28,10 @@ bool Drone::takeoff(float z){
28
return false;
29
}
30
else{
31
+ flying_status = true;
32
moveRelative({0,0,z,true});
33
// Here may need to sleep a while, then control if movement is done or still running.
34
// But for now I do not write such a thing
- flying_status = true;
35
return true;
36
37
@@ -214,8 +214,10 @@ int main(int argc, char **argv){
214
ros::init(argc, argv, "handler");
215
ros::NodeHandle nh;
216
ros::Rate rate(0.2);
217
+ Drone drone = Drone(nh);
218
+ drone.takeoff(5);
219
while(ros::ok()){
- position pos = {0,0,2,false};
220
+ position pos = {0,0,5,false};
221
rate.sleep();
222
223
0 commit comments