-
Notifications
You must be signed in to change notification settings - Fork 21
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
Showing
3 changed files
with
141 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,32 @@ | ||
<launch> | ||
<arg name="robot_name_1" default="tbmn_1" /> | ||
<arg name="drone_name_1" default="rmtt_0" /> | ||
<arg name="drone_name_2" default="rmtt_2" /> | ||
|
||
<!-- There is no need to launch tianbot mini --> | ||
|
||
<!-- There is no need to publish static tf from world to map, odom, etc. --> | ||
|
||
<!-- There is no odom published from tianbot mini --> | ||
|
||
<!-- publish static transform to link vrpn link to robot base_link --> | ||
<node pkg="tf" type="static_transform_publisher" name="robot_1_link" args="0 0 0 0 0 0 $(arg robot_name_1) $(arg robot_name_1)/base_link 20" /> | ||
<node pkg="tf" type="static_transform_publisher" name="drone_1_link" args="0 0 0 0 0 0 $(arg drone_name_1) $(arg drone_name_1)/base_link 20" /> | ||
<node pkg="tf" type="static_transform_publisher" name="drone_2_link" args="0 0 0 0 0 0 $(arg drone_name_2) $(arg drone_name_2)/base_link 20" /> | ||
|
||
<node pkg="abc_swarm" type="virtual_targets.py" name="virtual_targets" /> | ||
|
||
<node pkg="abc_swarm" type="tianbot_mini_tf.py" name="drone_1_follower" output="screen"> | ||
<param name="target_frame" value="rmtt_0_target" /> | ||
<param name="follower_robot_name" value="$(arg drone_name_1)" /> | ||
<param name="set_distance" value="0.3" /> | ||
</node> | ||
<node pkg="abc_swarm" type="tianbot_mini_tf.py" name="drone_2_follower" output="screen"> | ||
<param name="target_frame" value="rmtt_2_target" /> | ||
<param name="follower_robot_name" value="$(arg drone_name_2)" /> | ||
<param name="set_distance" value="0.3" /> | ||
</node> | ||
|
||
<!-- RVIZ可视化调试工具 --> | ||
<!-- <node name="rviz" pkg="rviz" type="rviz" args="-d $(find abc_swarm)/rviz/demo_formation.rviz" /> --> | ||
</launch> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,23 @@ | ||
<launch> | ||
<arg name="robot_name_1" default="tbmn_1" /> | ||
<arg name="drone_name_1" default="rmtt_0" /> | ||
|
||
<!-- There is no need to launch tianbot mini --> | ||
|
||
<!-- There is no need to publish static tf from world to map, odom, etc. --> | ||
|
||
<!-- There is no odom published from tianbot mini --> | ||
|
||
<!-- publish static transform to link vrpn link to robot base_link --> | ||
<node pkg="tf" type="static_transform_publisher" name="robot_1_link" args="0 0 0 0 0 0 $(arg robot_name_1) $(arg robot_name_1)/base_link 20" /> | ||
<node pkg="tf" type="static_transform_publisher" name="drone_1_link" args="0 0 0 0 0 0 $(arg drone_name_1) $(arg drone_name_1)/base_link 20" /> | ||
|
||
<node pkg="abc_swarm" type="tianbot_mini_tf.py" name="tianbot_mini_tf" output="screen"> | ||
<param name="target_frame" value="$(arg robot_name_1)" /> | ||
<param name="follower_robot_name" value="$(arg drone_name_1)" /> | ||
<param name="set_distance" value="0.3" /> | ||
</node> | ||
|
||
<!-- RVIZ可视化调试工具 --> | ||
<!-- <node name="rviz" pkg="rviz" type="rviz" args="-d $(find abc_swarm)/rviz/demo_formation.rviz" /> --> | ||
</launch> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,86 @@ | ||
#!/usr/bin/env python | ||
import math | ||
import rospy | ||
import tf | ||
from tf import transformations | ||
from tf import broadcaster | ||
import numpy as np | ||
|
||
def broadcaster(): | ||
rospy.init_node('virtual_target', anonymous=True) | ||
|
||
# read params | ||
center_frame = rospy.get_param('~center_frame', 'tbmn_1') | ||
radius = rospy.get_param('~radius', 0.5) | ||
target_frame = rospy.get_param('~target_frame', 'virtual_leader') | ||
linear_speed = rospy.get_param('~speed', 0.1) | ||
|
||
listener = tf.TransformListener() | ||
listener.waitForTransform(center_frame, "world", rospy.Time(0), rospy.Duration(3.0)); | ||
try: | ||
(trans, rot) = listener.lookupTransform("world", center_frame, rospy.Time()) | ||
except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException): | ||
pass | ||
|
||
br = tf.TransformBroadcaster() | ||
x = trans[0] | ||
y = trans[1] | ||
theta = 0 | ||
|
||
r = radius | ||
v = linear_speed | ||
a = v / r | ||
|
||
aligned_center_frame = center_frame + '_aligned' | ||
|
||
br.sendTransform((x, y, 0), | ||
tf.transformations.quaternion_from_euler(0, 0, 0), | ||
rospy.Time.now(), | ||
aligned_center_frame, | ||
"world") | ||
rospy.sleep(5) | ||
|
||
start = rospy.Time.now() | ||
rate = rospy.Rate(20) | ||
while not rospy.is_shutdown(): | ||
try: | ||
(trans, rot) = listener.lookupTransform("world", center_frame, rospy.Time()) | ||
except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException): | ||
continue | ||
|
||
x = trans[0] | ||
y = trans[1] | ||
theta = 0 | ||
br.sendTransform((x, y, 0), | ||
tf.transformations.quaternion_from_euler(0, 0, 0), | ||
rospy.Time.now(), | ||
aligned_center_frame, | ||
"world") | ||
|
||
t = (rospy.Time.now() - start).to_sec() | ||
theta = a * t | ||
x = r * math.sin(theta) | ||
y = - r * math.cos(theta) | ||
br.sendTransform((x, y, 0), | ||
tf.transformations.quaternion_from_euler(0, 0, theta), | ||
rospy.Time.now(), | ||
"rmtt_0_target", | ||
aligned_center_frame) | ||
|
||
theta = a * t + np.pi | ||
x = r * math.sin(theta) | ||
y = - r * math.cos(theta) | ||
br.sendTransform((x, y, 0), | ||
tf.transformations.quaternion_from_euler(0, 0, theta), | ||
rospy.Time.now(), | ||
"rmtt_2_target", | ||
aligned_center_frame) | ||
|
||
rate.sleep() | ||
|
||
|
||
if __name__ == '__main__': | ||
try: | ||
broadcaster() | ||
except rospy.ROSInterruptException: | ||
pass |