Skip to content

Commit

Permalink
Style fix for Ubuntu 24.04
Browse files Browse the repository at this point in the history
  • Loading branch information
KarthiAru committed Aug 29, 2024
1 parent 8925268 commit b3e8063
Showing 1 changed file with 42 additions and 11 deletions.
53 changes: 42 additions & 11 deletions examples/gimbal/gimbal.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,33 +97,60 @@ int main(int argc, char** argv)
std::cout << "Use yaw mode to lock to a specific direction...\n";

std::cout << "Look North...\n";
gimbal.set_angles(gimbal_id, 0.0f, 0.0f, -attitude.euler_angle_north.yaw_deg, Gimbal::GimbalMode::YawLock, Gimbal::SendMode::Once);
gimbal.set_angles(
gimbal_id,
0.0f,
0.0f,
-attitude.euler_angle_north.yaw_deg,
Gimbal::GimbalMode::YawLock,
Gimbal::SendMode::Once);
sleep_for(seconds(5));

std::cout << "Look East...\n";
gimbal.set_angles(gimbal_id, 0.0f, 0.0f, -attitude.euler_angle_north.yaw_deg + 90.0f, Gimbal::GimbalMode::YawLock, Gimbal::SendMode::Once);
gimbal.set_angles(
gimbal_id,
0.0f,
0.0f,
-attitude.euler_angle_north.yaw_deg + 90.0f,
Gimbal::GimbalMode::YawLock,
Gimbal::SendMode::Once);
sleep_for(seconds(5));

std::cout << "Look South...\n";
gimbal.set_angles(gimbal_id, 0.0f, 0.0f, -attitude.euler_angle_north.yaw_deg + 180.0f, Gimbal::GimbalMode::YawLock, Gimbal::SendMode::Once);
gimbal.set_angles(
gimbal_id,
0.0f,
0.0f,
-attitude.euler_angle_north.yaw_deg + 180.0f,
Gimbal::GimbalMode::YawLock,
Gimbal::SendMode::Once);
sleep_for(seconds(5));

std::cout << "Look West...\n";
gimbal.set_angles(gimbal_id, 0.0f, 0.0f, -attitude.euler_angle_north.yaw_deg -90.0f, Gimbal::GimbalMode::YawLock, Gimbal::SendMode::Once);
gimbal.set_angles(
gimbal_id,
0.0f,
0.0f,
-attitude.euler_angle_north.yaw_deg - 90.0f,
Gimbal::GimbalMode::YawLock,
Gimbal::SendMode::Once);
sleep_for(seconds(5));

std::cout << "Now use follow mode...\n";

std::cout << "And center first...\n";
gimbal.set_angles(gimbal_id, 0.0f, 0.0f, 0.0f, Gimbal::GimbalMode::YawFollow, Gimbal::SendMode::Once);
gimbal.set_angles(
gimbal_id, 0.0f, 0.0f, 0.0f, Gimbal::GimbalMode::YawFollow, Gimbal::SendMode::Once);
sleep_for(seconds(5));

std::cout << "Tilt gimbal down...\n";
gimbal.set_angles(gimbal_id, 0.0f, -90.0f, 0.0f, Gimbal::GimbalMode::YawFollow, Gimbal::SendMode::Once);
gimbal.set_angles(
gimbal_id, 0.0f, -90.0f, 0.0f, Gimbal::GimbalMode::YawFollow, Gimbal::SendMode::Once);
sleep_for(seconds(5));

std::cout << "Tilt gimbal back up...\n";
gimbal.set_angles(gimbal_id, 0.0f, 0.0f, 0.0f, Gimbal::GimbalMode::YawFollow, Gimbal::SendMode::Once);
gimbal.set_angles(
gimbal_id, 0.0f, 0.0f, 0.0f, Gimbal::GimbalMode::YawFollow, Gimbal::SendMode::Once);
sleep_for(seconds(5));

std::cout << "Slowly tilt up ...\n";
Expand All @@ -132,15 +159,18 @@ int main(int argc, char** argv)
sleep_for(seconds(5));

std::cout << "Back to horizontal...\n";
gimbal.set_angles(gimbal_id, 0.0f, 0.0f, 0.0f, Gimbal::GimbalMode::YawFollow, Gimbal::SendMode::Once);
gimbal.set_angles(
gimbal_id, 0.0f, 0.0f, 0.0f, Gimbal::GimbalMode::YawFollow, Gimbal::SendMode::Once);
sleep_for(seconds(5));

std::cout << "Pan to the right...\n";
gimbal.set_angles(gimbal_id, 0.0f, 0.0f, 90.0f, Gimbal::GimbalMode::YawFollow, Gimbal::SendMode::Once);
gimbal.set_angles(
gimbal_id, 0.0f, 0.0f, 90.0f, Gimbal::GimbalMode::YawFollow, Gimbal::SendMode::Once);
sleep_for(seconds(5));

std::cout << "Back to the center...\n";
gimbal.set_angles(gimbal_id, 0.0f, 0.0f, 0.0f, Gimbal::GimbalMode::YawFollow, Gimbal::SendMode::Once);
gimbal.set_angles(
gimbal_id, 0.0f, 0.0f, 0.0f, Gimbal::GimbalMode::YawFollow, Gimbal::SendMode::Once);
sleep_for(seconds(5));

std::cout << "Pan slowly to the left...\n";
Expand All @@ -149,7 +179,8 @@ int main(int argc, char** argv)
sleep_for(seconds(5));

std::cout << "Back to the center...\n";
gimbal.set_angles(gimbal_id, 0.0f, 0.0f, 0.0f, Gimbal::GimbalMode::YawFollow, Gimbal::SendMode::Once);
gimbal.set_angles(
gimbal_id, 0.0f, 0.0f, 0.0f, Gimbal::GimbalMode::YawFollow, Gimbal::SendMode::Once);
sleep_for(seconds(5));

std::cout << "Set ROI (region of interested) location...\n";
Expand Down

0 comments on commit b3e8063

Please sign in to comment.