Skip to content
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
2 changes: 2 additions & 0 deletions launch/swarmie.launch
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@
<param name="imu0" value="/$(arg name)/imu" />
<param name="two_d_mode" value="true" />
<param name="world_frame" value="odom" />
<param name="base_link_frame_output" value="$(arg name)/base_link" />
<param name="frequency" value="10" />

<rosparam param="odom0_config">[false, false, false,
Expand Down Expand Up @@ -80,6 +81,7 @@
<param name="imu0" value="/$(arg name)/imu" />
<param name="two_d_mode" value="true" />
<param name="world_frame" value="map" />
<param name="base_link_frame_output" value="$(arg name)/base_link" />
<param name="frequency" value="10" />

<rosparam param="odom0_config">[true, true, false,
Expand Down
4 changes: 2 additions & 2 deletions misc/rover_onboard_node_launch.sh
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,7 @@ rosparam set /$HOSTNAME\_ODOM/odom0 /$HOSTNAME/odom
rosparam set /$HOSTNAME\_ODOM/imu0 /$HOSTNAME/imu
rosparam set /$HOSTNAME\_ODOM/odom0_config [false,false,false,false,false,false,true,false,false,false,false,true,false,false,false]
rosparam set /$HOSTNAME\_ODOM/imu0_config [false,false,false,false,false,true,false,false,false,false,false,true,true,false,false]
nohup > logs/$HOSTNAME"_odom_EKF_log.txt" rosrun robot_localization ekf_localization_node _two_d_mode:=true _world_frame:=odom _frequency:=10 __name:=$HOSTNAME\_ODOM /odometry/filtered:=/$HOSTNAME/odom/filtered &
nohup > logs/$HOSTNAME"_odom_EKF_log.txt" rosrun robot_localization ekf_localization_node _two_d_mode:=true _world_frame:=odom _base_link_frame_output:=$HOSTNAME/base_link _frequency:=10 __name:=$HOSTNAME\_ODOM /odometry/filtered:=/$HOSTNAME/odom/filtered &

rosparam set /$HOSTNAME\_MAP/odom0 /$HOSTNAME/odom/navsat
rosparam set /$HOSTNAME\_MAP/odom1 /$HOSTNAME/odom/filtered
Expand Down Expand Up @@ -157,7 +157,7 @@ rosparam set $HOSTNAME\_MAP/process_noise_covariance "[0.005, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.1, 0, /
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.1]"

nohup > logs/$HOSTNAME"_map_EKF_log.txt" rosrun robot_localization ekf_localization_node _two_d_mode:=true _world_frame:=map _frequency:=10 __name:=$HOSTNAME\_MAP /odometry/filtered:=/$HOSTNAME/odom/ekf &
nohup > logs/$HOSTNAME"_map_EKF_log.txt" rosrun robot_localization ekf_localization_node _two_d_mode:=true _world_frame:=map _base_link_frame_output:=$HOSTNAME/base_link _frequency:=10 __name:=$HOSTNAME\_MAP /odometry/filtered:=/$HOSTNAME/odom/ekf &

throttle()
{
Expand Down