Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Joystick #273

Merged
merged 8 commits into from
Aug 11, 2023
Merged
Show file tree
Hide file tree
Changes from 5 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 8 additions & 1 deletion crazyflie/config/teleop.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -45,5 +45,12 @@
y: 0.0
z: 0.10
auto_yaw_rate: 0.0 # rad/s, use 0.0 for manual yaw control

takeoff:
duration: 1.0
height: 0.25
button: 6 # 7 start
land:
button: 7 # 6 back
emergency:
button: 2 # 1 red

2 changes: 1 addition & 1 deletion crazyflie/launch/launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -125,4 +125,4 @@ def generate_launch_description():
"use_sim_time": True,
}]
),
])
])
40 changes: 32 additions & 8 deletions crazyflie/src/teleop.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,18 @@ class TeleopNode : public rclcpp::Node
this->declare_parameter("cmd_vel_world.y_limit", rclcpp::PARAMETER_DOUBLE_ARRAY);
this->declare_parameter("cmd_vel_world.z_limit", rclcpp::PARAMETER_DOUBLE_ARRAY);

this->declare_parameter<float>("takeoff.duration");
this->get_parameter<float>("takeoff.duration", takeoff_paras_.duration);
this->declare_parameter<float>("takeoff.height");
this->get_parameter<float>("takeoff.height", takeoff_paras_.height);
this->declare_parameter<int>("takeoff.button");
this->get_parameter<int>("takeoff.button", takeoff_paras_.button);

this->declare_parameter<int>("land.button");
this->get_parameter<int>("land.button", land_button);
this->declare_parameter<int>("emergency.button");
this->get_parameter<int>("emergency.button", emergency_button);

on_mode_switched();

dt_ = 1.0f/frequency_;
Expand Down Expand Up @@ -132,6 +144,16 @@ class TeleopNode : public rclcpp::Node
return a;
}

struct
{
float duration;
float height;
int button;
} takeoff_paras_;

int land_button;
int emergency_button;

void on_parameter_event(const rcl_interfaces::msg::ParameterEvent &event)
{
if (event.node == "/teleop") {
Expand Down Expand Up @@ -195,15 +217,17 @@ class TeleopNode : public rclcpp::Node
{

static std::vector<int> lastButtonState(Xbox360Buttons::COUNT);


std::cout << "takeoff_paras_.button: " << takeoff_paras_.button << std::endl;
if (msg->buttons.size() >= Xbox360Buttons::COUNT && lastButtonState.size() >= Xbox360Buttons::COUNT) {
if (msg->buttons[Xbox360Buttons::Red] == 1 && lastButtonState[Xbox360Buttons::Red] == 0) {
if (msg->buttons[emergency_button] == 1 && lastButtonState[emergency_button] == 0) {
emergency();
}
if (msg->buttons[Xbox360Buttons::Start] == 1 && lastButtonState[Xbox360Buttons::Start] == 0) {

if (msg->buttons[takeoff_paras_.button] == 1 && lastButtonState[takeoff_paras_.button] == 0) {
takeoff();
}
if (msg->buttons[Xbox360Buttons::Back] == 1 && lastButtonState[Xbox360Buttons::Back] == 0) {
if (msg->buttons[land_button] == 1 && lastButtonState[land_button] == 0) {
land();
}
}
Expand Down Expand Up @@ -262,12 +286,12 @@ class TeleopNode : public rclcpp::Node
}
auto request = std::make_shared<Takeoff::Request>();
request->group_mask = 0;
request->height = 0.5;
request->duration = rclcpp::Duration::from_seconds(2);
request->height = takeoff_paras_.height;
request->duration = rclcpp::Duration::from_seconds(takeoff_paras_.duration);
client_takeoff_->async_send_request(request);

timer_takeoff_ = this->create_wall_timer(2s, [this]() {
state_.z = 0.5;
timer_takeoff_ = this->create_wall_timer(takeoff_paras_.duration, [this]() {
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Does this actually work for your locally? The CI reports the following error:

 [  8%] Building CXX object deps/crazyflie_tools/crazyflie_cpp/crazyflie-link-cpp/CMakeFiles/crazyflieLinkCpp.dir/src/Connection.cpp.o
  /__w/crazyswarm2/crazyswarm2/ros_ws/src/ypobr1p6gmn/crazyswarm2/crazyflie/src/teleop.cpp: In member function ‘void TeleopNode::takeoff()’:
  /__w/crazyswarm2/crazyswarm2/ros_ws/src/ypobr1p6gmn/crazyswarm2/crazyflie/src/teleop.cpp:297:10: error: no matching function for call to ‘TeleopNode::create_wall_timer(float&, TeleopNode::takeoff()::<lambda()>)’
    297 |         });
        |          ^
  In file included from /opt/ros/galactic/include/rclcpp/node.hpp:1329,
                   from /opt/ros/galactic/include/rclcpp/executors/single_threaded_executor.hpp:28,
                   from /opt/ros/galactic/include/rclcpp/executors.hpp:22,
                   from /opt/ros/galactic/include/rclcpp/rclcpp.hpp:156,
                   from /__w/crazyswarm2/crazyswarm2/ros_ws/src/ypobr1p6gmn/crazyswarm2/crazyflie/src/teleop.cpp:5:
  /opt/ros/galactic/include/rclcpp/node_impl.hpp:111:1: note: candidate: ‘template<class DurationRepT, class DurationT, class CallbackT> typename rclcpp::WallTimer<CallbackT>::SharedPtr rclcpp::Node::create_wall_timer(std::chrono::duration<_Rep1, _Period1>, CallbackT, rclcpp::CallbackGroup::SharedPtr)’
    111 | Node::create_wall_timer(
        | ^~~~
  /opt/ros/galactic/include/rclcpp/node_impl.hpp:111:1: note:   template argument deduction/substitution failed:
  /__w/crazyswarm2/crazyswarm2/ros_ws/src/ypobr1p6gmn/crazyswarm2/crazyflie/src/teleop.cpp:297:10: note:   mismatched types ‘std::chrono::duration<_Rep1, _Period1>’ and ‘float’
    297 |         });
        |          ^
  [ 11%] Building CXX object deps/crazyflie_tools/crazyflie_cpp/crazyflie-link-cpp/CMakeFiles/crazyflieLinkCpp.dir/src/USBDevice.cpp.o
  [ 13%] Building CXX object deps/crazyflie_tools/crazyflie_cpp/crazyflie-link-cpp/CMakeFiles/crazyflieLinkCpp.dir/src/Crazyradio.cpp.o
  [ 16%] Building CXX object deps/crazyflie_tools/crazyflie_cpp/crazyflie-link-cpp/CMakeFiles/crazyflieLinkCpp.dir/src/CrazyradioThread.cpp.o
  [ 19%] Building CXX object deps/crazyflie_tools/crazyflie_cpp/crazyflie-link-cpp/CMakeFiles/crazyflieLinkCpp.dir/src/CrazyflieUSB.cpp.o
  [ 22%] Building CXX object deps/crazyflie_tools/crazyflie_cpp/crazyflie-link-cpp/CMakeFiles/crazyflieLinkCpp.dir/src/CrazyflieUSBThread.cpp.o
  make[2]: *** [CMakeFiles/teleop.dir/build.make:63: CMakeFiles/teleop.dir/src/teleop.cpp.o] Error 1
  make[1]: *** [CMakeFiles/Makefile2:184: CMakeFiles/teleop.dir/all] Error 2
  make[1]: *** Waiting for unfinished jobs....
  [ 25%] Building CXX object deps/crazyflie_tools/crazyflie_cpp/crazyflie-link-cpp/CMakeFiles/crazyflieLinkCpp.dir/src/Version.cpp.o
  [ 27%] Linking CXX static library libcrazyflieLinkCpp.a
  [ 27%] Built target crazyflieLinkCpp
  make: *** [Makefile:141: all] Error 2
  ---
  --- stderr: crazyflie
  /__w/crazyswarm2/crazyswarm2/ros_ws/src/ypobr1p6gmn/crazyswarm2/crazyflie/src/teleop.cpp: In member function ‘void TeleopNode::takeoff()’:
  /__w/crazyswarm2/crazyswarm2/ros_ws/src/ypobr1p6gmn/crazyswarm2/crazyflie/src/teleop.cpp:297:10: error: no matching function for call to ‘TeleopNode::create_wall_timer(float&, TeleopNode::takeoff()::<lambda()>)’
    297 |         });
        |          ^
  In file included from /opt/ros/galactic/include/rclcpp/node.hpp:1329,
                   from /opt/ros/galactic/include/rclcpp/executors/single_threaded_executor.hpp:28,
                   from /opt/ros/galactic/include/rclcpp/executors.hpp:22,
                   from /opt/ros/galactic/include/rclcpp/rclcpp.hpp:156,
                   from /__w/crazyswarm2/crazyswarm2/ros_ws/src/ypobr1p6gmn/crazyswarm2/crazyflie/src/teleop.cpp:5:
  /opt/ros/galactic/include/rclcpp/node_impl.hpp:111:1: note: candidate: ‘template<class DurationRepT, class DurationT, class CallbackT> typename rclcpp::WallTimer<CallbackT>::SharedPtr rclcpp::Node::create_wall_timer(std::chrono::duration<_Rep1, _Period1>, CallbackT, rclcpp::CallbackGroup::SharedPtr)’
    111 | Node::create_wall_timer(
        | ^~~~
  /opt/ros/galactic/include/rclcpp/node_impl.hpp:111:1: note:   template argument deduction/substitution failed:
  /__w/crazyswarm2/crazyswarm2/ros_ws/src/ypobr1p6gmn/crazyswarm2/crazyflie/src/teleop.cpp:297:10: note:   mismatched types ‘std::chrono::duration<_Rep1, _Period1>’ and ‘float’
    297 |         });
        |          ^
  make[2]: *** [CMakeFiles/teleop.dir/build.make:63: CMakeFiles/teleop.dir/src/teleop.cpp.o] Error 1
  make[1]: *** [CMakeFiles/Makefile2:184: CMakeFiles/teleop.dir/all] Error 2
  make[1]: *** Waiting for unfinished jobs....
  make: *** [Makefile:141: all] Error 2
  ---
  Failed   <<< crazyflie [11.7s, exited with code 2]

state_.z = takeoff_paras_.height;
is_low_level_flight_active_ = true;
this->timer_takeoff_->cancel();
});
Expand Down
Loading