Skip to content
Merged
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
19 changes: 19 additions & 0 deletions phoenix_description/urdf/phoenix.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -393,6 +393,25 @@
<child link="vectornav"/>
</joint>

<!-- Dummy link to match the GPS frame_id -->
<link name="imu_link">
<visual>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
</visual>
<inertial>
<mass value="0.001"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
</inertial>
</link>

<joint name="imu_link_to_vectornav" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="vectornav"/>
<child link="imu_link"/>
</joint>

<!-- Gazebo Plugins -->

<gazebo>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,12 +31,8 @@
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
<<<<<<< HEAD
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution

=======
from launch.substitutions import PathJoinSubstitution
>>>>>>> 81e19a3 (Fixed: PathJoinSubstitution updated teleop_ack_Rc included in gazeebo and robot)

def generate_launch_description():
pkg_share = get_package_share_directory('phoenix_robot')
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,11 +23,11 @@ navsat_transform_node:
zero_altitude: false

# If this is true, the transform world_frame->utm transform is broadcast for use by other nodes. Defaults to false.
broadcast_utm_transform: false
broadcast_utm_transform: true

# If this is true, the utm->world_frame transform will be published instead of the world_frame->utm transform.
# Note that broadcast_utm_transform still has to be enabled. Defaults to false.
broadcast_utm_transform_as_parent_frame: false
broadcast_utm_transform_as_parent_frame: true

# If this is true, all received odometry data is converted back to a lat/lon and published as a NavSatFix message as
# /gps/filtered. Defaults to false.
Expand All @@ -37,7 +37,7 @@ navsat_transform_node:
# /odometry/filtered topic coming from one of robot_localization's state estimation nodes). BE CAREFUL when using this!
# The yaw value in your odometry source *must* be world-referenced, e.g., you cannot use your odometry source for yaw
# if your yaw data is based purely on integrated velocities. Defaults to false.
use_odometry_yaw: false
use_odometry_yaw: true

# If true, will retrieve the datum from the 'datum' parameter below, if available. If no 'datum' parameter exists,
# navsat_transform_node will wait until the user calls the 'datum' service with the SetDatum service message.
Expand All @@ -47,5 +47,6 @@ navsat_transform_node:
# origin (datum) using this parameter. The fields in the parameter represent latitude and longitude in decimal degrees,
# and heading in radians. As navsat_transform_node assumes an ENU standard, a 0 heading corresponds to east.
# wait this might actually be usefully for translating over maps lol -AFB
# NOTE WE
datum: [55.944904, -3.186693, 0.0]

This file was deleted.

5 changes: 5 additions & 0 deletions phoenix_robot/config/phnx_io_ros/phnx_io_ros.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
/phnx_io_ros:
ros__parameters:
kP: 1.0
kI: 1.0
kD: 0.1
Original file line number Diff line number Diff line change
Expand Up @@ -23,9 +23,9 @@ ekf_filter_node_odom:
# vr vp vy
# ax ay az

imu0: /phoenix/gps/imu #
imu0: /phoenix/imu
imu0_config: [false, false, false,
true, true, true,
false, false, false,
false, false, false,
true, true, true,
true, true, true]
Expand Down Expand Up @@ -66,4 +66,4 @@ ekf_filter_node_map:
false, false, false,
false, false, false,
false, false, false]
odom1_differential: false
odom1_differential: false
Original file line number Diff line number Diff line change
@@ -1,4 +1,7 @@
### ekf config file ###

### THIS IS LAST YEARS EKF CONFIG LEAVE AS IS ###

ekf_filter_node:
ros__parameters:
# The frequency, in Hz, at which the filter will output a position estimate. Note that the filter will not begin
Expand Down
Loading
Loading