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 4 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
23 changes: 23 additions & 0 deletions .vscode/c_cpp_properties.json
Copy link

Choose a reason for hiding this comment

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

Please don't include any .vscode file

Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
{
"configurations": [
{
"browse": {
"databaseFilename": "${default}",
"limitSymbolsToIncludedHeaders": false
},
"includePath": [
"/home/nan/ros2_ws/install/motion_capture_tracking_interfaces/include/**",
"/home/nan/ros2_ws/install/crazyflie_interfaces/include/**",
"/opt/ros/humble/include/**",
"/home/nan/ros2_ws/src/figure_trajectory/include/**",
"/usr/include/**"
],
"name": "ROS",
"intelliSenseMode": "gcc-arm64",
"compilerPath": "/usr/bin/gcc",
"cStandard": "gnu11",
"cppStandard": "c++14"
}
],
"version": 4
}
30 changes: 30 additions & 0 deletions .vscode/settings.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
{
"python.autoComplete.extraPaths": [
"/home/nan/crazyflie-firmware/build",
"/home/nan/ros2_ws/build/my_robot_controller",
"/home/nan/ros2_ws/install/my_robot_controller/lib/python3.10/site-packages",
"/home/nan/ros2_ws/install/motion_capture_tracking_interfaces/local/lib/python3.10/dist-packages",
"/home/nan/ros2_ws/install/figure_trajectory/local/lib/python3.10/dist-packages",
"/home/nan/ros2_ws/install/crazyflie_sim/local/lib/python3.10/dist-packages",
"/home/nan/ros2_ws/install/crazyflie_examples/local/lib/python3.10/dist-packages",
"/home/nan/ros2_ws/build/crazyflie_py",
"/home/nan/ros2_ws/install/crazyflie_py/lib/python3.10/site-packages",
"/home/nan/ros2_ws/install/crazyflie_interfaces/local/lib/python3.10/dist-packages",
"/opt/ros/humble/lib/python3.10/site-packages",
"/opt/ros/humble/local/lib/python3.10/dist-packages"
],
"python.analysis.extraPaths": [
"/home/nan/crazyflie-firmware/build",
"/home/nan/ros2_ws/build/my_robot_controller",
"/home/nan/ros2_ws/install/my_robot_controller/lib/python3.10/site-packages",
"/home/nan/ros2_ws/install/motion_capture_tracking_interfaces/local/lib/python3.10/dist-packages",
"/home/nan/ros2_ws/install/figure_trajectory/local/lib/python3.10/dist-packages",
"/home/nan/ros2_ws/install/crazyflie_sim/local/lib/python3.10/dist-packages",
"/home/nan/ros2_ws/install/crazyflie_examples/local/lib/python3.10/dist-packages",
"/home/nan/ros2_ws/build/crazyflie_py",
"/home/nan/ros2_ws/install/crazyflie_py/lib/python3.10/site-packages",
"/home/nan/ros2_ws/install/crazyflie_interfaces/local/lib/python3.10/dist-packages",
"/opt/ros/humble/lib/python3.10/site-packages",
"/opt/ros/humble/local/lib/python3.10/dist-packages"
]
}
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_paras:
NannCai marked this conversation as resolved.
Show resolved Hide resolved
duration: 1.0
height: 0.25
button: 6 # 7 start
land_paras:
Copy link

Choose a reason for hiding this comment

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

land:

button: 7 # 6 back
emergency_paras:
Copy link

Choose a reason for hiding this comment

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

emergency

button: 2 # 1 red

10 changes: 5 additions & 5 deletions crazyflie/launch/launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -76,11 +76,11 @@ def generate_launch_description():
name='teleop',
remappings=[
('emergency', 'all/emergency'),
('takeoff', 'cf6/takeoff'),
('land', 'cf6/land'),
('cmd_vel_legacy', 'cf6/cmd_vel_legacy'),
('cmd_full_state', 'cf6/cmd_full_state'),
('notify_setpoints_stop', 'cf6/notify_setpoints_stop'),
('takeoff', 'all/takeoff'),
('land', 'all/land'),
('cmd_vel_legacy', 'all/cmd_vel_legacy'),
Copy link

Choose a reason for hiding this comment

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

those two should not be changed to all.

('cmd_full_state', 'all/cmd_full_state'),
('notify_setpoints_stop', 'all/notify_setpoints_stop'),
],
parameters=[teleop_params]
),
Expand Down
38 changes: 31 additions & 7 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_paras.duration");
this->get_parameter<float>("takeoff_paras.duration", takeoff_paras_.duration);
this->declare_parameter<float>("takeoff_paras.height");
this->get_parameter<float>("takeoff_paras.height", takeoff_paras_.height);
this->declare_parameter<int>("takeoff_paras.button");
this->get_parameter<int>("takeoff_paras.button", takeoff_paras_.button);

this->declare_parameter<int>("land_paras.button");
this->get_parameter<int>("land_paras.button", land_button);
this->declare_parameter<int>("emergency_paras.button");
this->get_parameter<int>("emergency_paras.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]() {
Copy link

Choose a reason for hiding this comment

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

the 2s also needs to be changed

state_.z = 0.5;
state_.z = takeoff_paras_.height; // Is here right? should I change the 2s in line 293
Copy link

Choose a reason for hiding this comment

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

this is correct, and yes, the 2s also need to be changed.

is_low_level_flight_active_ = true;
this->timer_takeoff_->cancel();
});
Expand Down