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

Zero cmd_vel on takeoff, reset, and land. #160

Open
wants to merge 3 commits into
base: indigo-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all 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
59 changes: 59 additions & 0 deletions config/log710.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,59 @@
# Logitech F710 wireless controller
# Deadman (enable) button: Right Trigger
teleop:
piloting:
type: topic
message_type: "geometry_msgs/Twist"
topic_name: /cmd_vel
deadman_buttons: [7]
axis_mappings:
-
axis: 3 # Right thumb stick (up/down)
target: linear.x
scale: 1.0
offset: 0.0
-
axis: 2 # Right thumb stick (left/right)
target: linear.y
scale: -1.0
offset: 0.0
-
axis: 1 # Left thumb stick (up/down)
target: linear.z
scale: 1.0
offset: 0.0
-
axis: 0 # Left thumb stick (left/right)
target: angular.z
scale: -1.0
offset: 0.0
takeoff:
type: topic
message_type: "std_msgs/Empty"
topic_name: takeoff
deadman_buttons: [3, 7] # RT + Y
axis_mappings: []
land:
type: topic
message_type: "std_msgs/Empty"
topic_name: land
deadman_buttons: [1, 7] # RT + A
axis_mappings: []
emergency:
type: topic
message_type: "std_msgs/Empty"
topic_name: reset
deadman_buttons: [2, 7] # RT + B
axis_mappings: []
reset:
type: topic
message_type: "std_msgs/Empty"
topic_name: reset
deadman_buttons: [4, 5] # RT + X
axis_mappings: []
flip:
type: topic
message_type: "std_msgs/UInt8"
topic_name: flip
deadman_buttons: [6, 7, 0] # RT + LT + X
axis_mappings: []
22 changes: 22 additions & 0 deletions launch/joy_teleop.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
<?xml version="1.0" ?>
<!-- based on example launch files from joy_teleop and teleop_twist_joy packages -->
<!-- TODO(BUG): group tag prevents this file to be included cleanly from other launch files -->
<launch>
<arg name="joy_dev" default="/dev/input/js0" />
<arg name="joy_config" default="log710" />
<arg name="teleop_config" default="$(find ardrone_autonomy)/config/$(arg joy_config).yaml" />

<group ns="ardrone">
<rosparam file="$(arg teleop_config)" command="load" />

<node pkg="joy" type="joy_node" name="joy_node">
<param name="dev" value="$(arg joy_dev)" />
<param name="deadzone" value="0.2" />
<param name="autorepeat_rate" value="20" />
</node>

<node pkg="joy_teleop" type="joy_teleop.py" name="joy_teleop">
</node>
</group>

</launch>
2 changes: 2 additions & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,8 @@
<run_depend>camera_info_manager</run_depend>
<run_depend>message_runtime</run_depend>
<run_depend>nav_msgs</run_depend>
<run_depend>joy</run_depend>
<run_depend>joy_teleop</run_depend>

<export>
<rosdoc config="rosdoc.yaml"/>
Expand Down
13 changes: 13 additions & 0 deletions src/teleop_twist.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -160,24 +160,37 @@ void CmdVelCallback(const geometry_msgs::TwistConstPtr &msg)
vp_os_mutex_unlock(&twist_lock);
}

void ZeroCmdVel()
{
cmd_vel.linear.x = 0.0;
cmd_vel.linear.y = 0.0;
cmd_vel.linear.z = 0.0;
cmd_vel.angular.x = 0.0;
cmd_vel.angular.y = 0.0;
cmd_vel.angular.z = 0.0;
}

void LandCallback(const std_msgs::Empty &msg)
{
vp_os_mutex_lock(&twist_lock);
needs_land = true;
ZeroCmdVel();
vp_os_mutex_unlock(&twist_lock);
}

void ResetCallback(const std_msgs::Empty &msg)
{
vp_os_mutex_lock(&twist_lock);
needs_reset = true;
ZeroCmdVel();
vp_os_mutex_unlock(&twist_lock);
}

void TakeoffCallback(const std_msgs::Empty &msg)
{
vp_os_mutex_lock(&twist_lock);
needs_takeoff = true;
ZeroCmdVel();
vp_os_mutex_unlock(&twist_lock);
}

Expand Down