Skip to content

Commit

Permalink
Some quick things to test for EBS control - using global frame over l…
Browse files Browse the repository at this point in the history
…ocal
  • Loading branch information
b1n-ch1kn committed Oct 9, 2024
1 parent b9ab06e commit 0f5a8d5
Show file tree
Hide file tree
Showing 4 changed files with 16 additions and 27 deletions.
27 changes: 4 additions & 23 deletions src/common/vehicle_urdf/urdf/sensors.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -2,38 +2,19 @@
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="velodyne" params="*origin parent name">
<!-- base frame to velodyne base -->
<joint name="${name}_base_mount_joint" type="fixed">
<joint name="${name}_base_mount_joint" type="fixed">
<xacro:insert_block name="origin" />
<parent link="${parent}"/>
<child link="${name}_base_link"/>
</joint>

<link name="${name}_base_link">
<visual>
<geometry>
<mesh filename="file://$(find vehicle_urdf)/meshes/VLP16_base_1.dae" />
</geometry>
</visual>
<visual>
<geometry>
<mesh filename="file://$(find vehicle_urdf)/meshes/VLP16_base_2.dae" />
</geometry>
</visual>
</link>

<!-- velodyne base to velodyne scan -->
<joint name="${name}_base_scan_joint" type="fixed" >
<origin xyz="0 0 0.0377" rpy="0 0 0" />
<parent link="${name}_base_link" />
<child link="${name}"/>
</joint>

<link name="${name}">
<visual>
<origin xyz="0 0 -0.0377" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find vehicle_urdf)/meshes/VLP16_scan.dae" />
<cylinder radius="0.0516" length="0.0717"/>
</geometry>
<material name="black"/>
</visual>
</link>
</xacro:macro>
Expand Down
11 changes: 9 additions & 2 deletions src/operations/mission_controller/launch/ebs_test.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,13 @@ def generate_launch_description():
)
),
# mapping/planning
Node(
package="map_creation",
executable="cone_placement_node",
parameters=[
get_package_share_path("map_creation") / "config" / "cone_placement.yaml",
],
),
Node(
package="planners",
executable="ft_planner_node",
Expand All @@ -30,9 +37,9 @@ def generate_launch_description():
],
ros_arguments=[
"-p",
"topic_name:=lidar/cone_detection",
"topic_name:=slam/global_map",
"-p",
"target_frame:=base_footprint",
"target_frame:=track",
],
),
# guidance/control
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -177,5 +177,5 @@ def main(args=None):
rclpy.init(args=args)
node = EBSTestHandler()
rclpy.spin(node)
# node.destroy_node()
node.destroy_node()
rclpy.shutdown()
3 changes: 2 additions & 1 deletion tools/play_bag.sh
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,9 @@ source install/setup.bash
# BAG_CMD="ros2 bag play -s mcap /mnt/e/rosbag2_2024_07_25-03_24_19/ --clock -p" # lidar on roll hoop test
# BAG_CMD="ros2 bag play -s mcap /mnt/e/rosbag2_2024_07_25-05_04_46/ --clock -p" # half lap
# BAG_CMD="ros2 bag play -s mcap /mnt/e/rosbag2_2024_07_25-05_18_42/ --clock -p" # other half of lap
BAG_CMD="ros2 bag play -s mcap /mnt/e/rosbag2_2024_09_04-05_14_43/ --clock -p" # 2.5 laps
# BAG_CMD="ros2 bag play -s mcap /mnt/e/rosbag2_2024_09_04-05_14_43/ --clock -p" # 2.5 laps
# BAG_CMD="ros2 bag play -s mcap /mnt/e/rosbag2_2024_09_24-06_08_59/ --clock -p" # 1 lap, loop close crashing
BAG_CMD="ros2 bag play -s mcap /mnt/e/rosbag2_2024_09_24-02_16_55/ --clock -p" # ebs test run

REMAPPINGS=(
# /tf:=/tf_old
Expand Down

0 comments on commit 0f5a8d5

Please sign in to comment.