-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathhover_bendable.launch
59 lines (51 loc) · 2.38 KB
/
hover_bendable.launch
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
<?xml version="1.0"?>
<launch>
<arg name="joy_dev" default="/dev/input/js0" />
<rosparam command="load" file="$(find crazyswarm)/launch/crazyflieTypes.yaml" />
<rosparam command="load" file="$(find crazyswarm)/launch/bendable_cfs.yaml" />
<!-- <node name = "niceHover" pkg="crazyswarm" type = "niceHover.py" output = "screen"/> -->
<node pkg="crazyswarm" type="crazyswarm_server" name="crazyswarm_server" output="screen" >
<rosparam>
<!-- # Logging configuration (Use enable_logging to actually enable logging)
genericLogTopics: ["log1"]
genericLogTopicFrequencies: [10]
genericLogTopic_log1_Variables: ["stateEstimate.x", "ctrltarget.x"] -->
# firmware parameters for all drones (use crazyflieTypes.yaml to set per type, or
# allCrazyflies.yaml to set per drone)
firmwareParams:
commander:
enHighLevel: 1
stabilizer:
estimator: 2 # 1: complementary, 2: kalman
controller: 2 # 1: PID, 2: mellinger
locSrv:
extPosStdDev: 1e-3
extQuatStdDev: 0.5e-1
kalman:
resetEstimation: 1
# tracking
motion_capture_type: "optitrack"
object_tracking_type: "motionCapture"
motion_capture_host_name: "192.168.0.4"
send_position_only: False # set to False to send position+orientation; set to True to send position only
# motion_capture_interface_ip: "192.168.0.4" # optional for optitrack with multiple interfaces
save_point_clouds: "/dev/null" # set to a valid path to log mocap point cloud binary file.
print_latency: False
write_csvs: False
force_no_cache: False
enable_parameters: True
enable_logging: False
enable_logging_pose: True
</rosparam>
</node>
<node name="joy" pkg="joy" type="joy_node" output="screen">
<param name="dev" value="$(arg joy_dev)" />
</node>
<node pkg="crazyswarm" type="crazyswarm_teleop" name="crazyswarm_teleop" output="screen">
<param name="csv_file" value="$(find crazyswarm)/launch/figure8_smooth.csv" />
<param name="timescale" value="0.8" />
</node>
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find crazyswarm)/launch/test.rviz"/>
<!-- <node pkg="rqt_plot" type="rqt_plot" name="rqt_plot_x" args="/cf2/log1/values[0]"/> -->
<!-- <node pkg="rqt_plot" type="rqt_plot" name="rqt_plot_roll" args="/cf1/log1/values[2] /cf1/log1/values[3]"/> -->
</launch>