Skip to content

Commit

Permalink
Release 1.4.0 (#348)
Browse files Browse the repository at this point in the history
* Fix URDF mesh, ports, and lidar
- URDF mesh now points to /home/share on Quad. 3D model works in Rviz2
- Port for CARLA now points to 2000+domain id
- Domain ID of 14 => -world-port=2014
- Domain ID now passed to Docker from host on boot
- Fixed error with lidar processing node
- Removed one last reference to AllStar
- Deleted stale 3D models from /data
:sparkles:  Add Guardian node
:sparkles: Add working CARLA simulation agent (`carla.launch.py`)
:sparkles:  Add junction management node (basic FSM)
:sparkles:  Add grid summation node
:sparkles: Add RTP, the recursive tree planner, with inbuilt motion control
:sparkles:  Add airbags, a low-level emergency braking system

Numerous other refinements and integrations in preparation for real-world use! See below
---
* Copy ground seg code over from Stepan

* Comment out log message

* Fix package boilerplate

* fixed/modified subsriber, publisher for dynamic_grid

* occupancy grid appears in rviz2

* Update index.md

* Removed old EvidentialGrid msgs, OccupancyGrid now in use for Egma

* - Fixed egma.msg
- Added ROS_DOMAIN_ID to carla bridge port

* Removed refrence to nonfunctional rrt node, fixed error in lite launch

* Updated reference to cycloneDDS in dockerfile

* Add MCL, mapping tools, and leaderboard connection improvments (#303)

* Initial commit

* Fix MCL import, PCD read in mcl_node

* Add octomap package

* Add PCL conversion

* Add tree.insertPointCloud

* Mapping works

* Edit Docker files, gitignore

* Add Rviz2 to launch

* Source Navigator. Does not appear to work 100%...

* It crashes immediately 🥲

* Add repub to world info in map_management_node

* Begin mapping doc

* Fixed runtime error

* Add to mapping doc

* Add cube list visuals for voxel map

* Switch to PointCloud2 for visuals.
- Much faster.
- Can still be shown as voxels ("boxes") in Rviz2

* Rename to OctoSlam, add MCL boilerplate

* Add particle visualization (kinda)

* Fix intial covariance, add more boilerplate

* General updates to particle filter

* Add diagnostic pub

* Move tf broadcasting to OctoSlam

* Revise predictParticleMotion

* Adjust height cutoff function in lidar_processing

* Escape pointer hell

* Ignore map files

* Separate weights into another vector

* Add (dubious) performance timers

* Move quatToYaw to Eigen. It ((sorta)) works

* Plot lane boundaries in map_management

* Add opendrivepy

* Add road parsing

* Add  to opendrivepy

* Contains kinda works, shows image

* Fix overlap in junctions, add tqdm

* Map grid now shown in Rviz

* Fix occupancy grid origin

* Add Roger Labbe's code

* Add to mcl.py

* Add semantic lidar (road only)

* Add to MCL.step()

* Transforms published

* Add particle vis

* Write alignment for update_weights

* Continuing to tune MCL

* All green lights

* Finished with MCL for now :(

* Fix yaw issue with MCL

* Refactor topic names and MCL code

* Fix MCL init error to far from GNSS

* Dust off the Leaderboard connection workflow

* Move to Town12

* Add libopendrive, map_management_cpp

* Finish get_lane_polygons.
- Plotting works.
- Still need to generate occupancy grid...

* Improve efficiency of getOccupancyGrid

* MapManager now publishes drivable grid

* Add to map manager

* Map now loads from /carla/world_info

* Refactor, fix leaderboard

* Rename voltron_msgs to nova_msgs

* Rename `map_management_cpp` to `map_management`
- Fix build tool error with libopendrive

* Add segmentation pkg

* Add mmseg to /mmsegmentation
- Install with Dockerfile

* Add mmseg to image_segmentation_node (again)

* Update main.yml

Edit main.yaml to build Navigator using latest Docker image

* Update action to use checkout#v3

* Complete 2D image segmentation

* Add ROSOccupancyGridPrediction
- Also remove dynamic_grid_old

* Create occupancy_cpp package

* Add to GroundSegmentationNode

* Fixed "PCL can not be found" with symlink

* Add to docs

* Added MRF ground filtering

* Add StaticOccupancyNode

* Add ground seg to carla.launch.py

* Add to getLanesFromRouteMsg

* Fix path publication

* add points to DST logic implemented

* Cleaned up

* Completed add free spaces and add ego vehicle logic. Cleaned up as well. Still needs some adustment

* Added header file, nova_msgs build error

* Add to route manipulation

* Debugging, symbol lookup error

* Comment out "masses" references

* Fix map_manager, remove prob_0

* Finish removal of prob_0

* Remove occupancy_msg

* Add debug to add_points_to_the_DST

* Remove PI, got "did not match a case"

* Add routing to MapManager

* Finish routing for now
- It's jank
- We're going to move on anyway 👍

* Rename MapManager members

* Add simple_route_controller

* Fixed slope error, now publishes. Grid values incorrect.

* Refactored names. Easier to read.

* Add route distance costmap

* Route distance now continuous
- Distance previous was relative to closest route point, which created a series of circles
- Distance now relative to linestring, creating a tube shape

* Changed doubles to floats. Grid works! I think it's rotated incorrectly though

* Add to docs

* Add to docs

* Add 3D semantic segmentation (#320)

* Begin adapatation of BerensRWU/DenseMap

* LiDAR->image projection kinda works

* Add documentation, wrap up

* Add to launch

* Add NPC car spawning

* Add walker spawn

* Got rid of more doubles, changed subscribed topic to ground seg node. Still flipped and rotated incorrectly??

* Begin to switch mcl to base_link grid

* Add flat surface grid

* Steady progress.
Need to adjust dims of drivable area grid.

* Adjust map publisher dimensions

* Still not quite right.

* Adjusting for loop iteration to see if that helps

* Converted tesor and mass callback function

* Keeping this configuration for now, still rotated

* Begin move to speedometer for motion prediction

* Finish addition of speedometer data

* Re-add weights, but car is jumpy in motion

* Hits calculation now fixed

* Fixed an oopsie with getMotionDelta

* Still jank :`(

* Add kidnap warning, noise

* Incomplete switch to voting method

* Switched rows and columns, sort of working now

* Testing stage for prednet node

* Now ignores points outside of boundary. Near perfect, H/V raytracing needs work

* Logic is done! I concede to minor anomalies. Refactoring and masses TODO

* Updated installation instructions

* Speed up semantic segmentation

* Semantic LiDAR is now colorized

* Masses time

* Re-add particle-on-grid transforms

* Back to square one. Kinda works, not really

* Add pole penalty

* Add highly accurate dead reckoning

* Add "tricks" page

* Switch to "semantic" grid map

* Add map object tree

* Add signals

* Add getLandmarks

* Get nearest landmark

* Re-add original weight update

* Static Grid Exe now runs through main stack

* Fixed nav_msgs undefined symbol error. Masses now working.

* created epas node

* Refactored and documented code. Still needs more refactoring but ready for use.

* Add alternate logo

* Battling memory issues in MapManagementNode

* added can communication logic to epas node

* Adjust Dockerfile

* Pulled from odev

* Add to mcl.py

* Done for now

* Begin to re-introduce traffic light points

* Fix StaticOccupancy build error, remove LGSVL msgs

* Final touches

* Add GNSS averaging node

* Add subscriptions

* Changed constant names, builds and runs correctly.

* Add localization with MCL and semantic segmentation (#326)

* Begin move to speedometer for motion prediction

* Finish addition of speedometer data

* Re-add weights, but car is jumpy in motion

* Hits calculation now fixed

* Fixed an oopsie with getMotionDelta

* Still jank :`(

* Add kidnap warning, noise

* Incomplete switch to voting method

* Speed up semantic segmentation

* Semantic LiDAR is now colorized

* Re-add particle-on-grid transforms

* Back to square one. Kinda works, not really

* Add pole penalty

* Add highly accurate dead reckoning

* Add "tricks" page

* Switch to "semantic" grid map

* Add map object tree

* Add signals

* Add getLandmarks

* Get nearest landmark

* Re-add original weight update

* Add alternate logo

* Battling memory issues in MapManagementNode

* Add to mcl.py

* Done for now

* Begin to re-introduce traffic light points

* Fix StaticOccupancy build error, remove LGSVL msgs

* Final touches

* Add documentation and RTPS files

* Add untracked documentation

* Resolve merge conflict

* Upaded package json

* Moved prednet models to data directory, fixed reference in node file

* finished coding epas_node

* Remove reference to lanelet

* add throttle_node

* Initial commit for parade controller

* Add GNSS averaging node
- Error is between 0.7-2.0 meters
- Likely projection error b/w CARLA, pymap3d

* Updated UTM projection function

* Fix memory leak, add docs to image_segmentation

* Add diagnostics to gnss averager

* Starting searching for predent import fix

* Fix most build errors
- StaticOccupancy variable mismatch
- X forwarding
-  Lanelet missing

* Finished prednet node

* Rotated Grid & Changed to Egma message

* created, built and ran joy node

* created subsriber for epas_node

* Finished comments on prednet node

* Moved packages to parade launch file, added joy_linux driver

* Add linear actuator node

* Removed carla packages, changed port to ACM1

* Parade controller package creation

* Changed param files to left and right, TODO: add remaining driver/scan packages

* Add throttle control node

* Update EPAS and MCU interface packages

* Changed file header

* Add grid summation/cost map generation (#337)

* created epas node

* added can communication logic to epas node

* Adjust Dockerfile

* finished coding epas_node

* Remove reference to lanelet

* add throttle_node

* Fix most build errors
- StaticOccupancy variable mismatch
- X forwarding
-  Lanelet missing

* created, built and ran joy node

* created subsriber for epas_node

* Moved packages to parade launch file, added joy_linux driver

* Add linear actuator node

* Removed carla packages, changed port to ACM1

* Parade controller package creation

* Changed param files to left and right, TODO: add remaining driver/scan packages

* Add throttle control node

* Update EPAS and MCU interface packages

* Add grid summation node

* Add to grid summation, docker.sh

* Fix launch file, move parade controller

* Add to grid summation

* Add grid summation to leaderboard workflow

---------

Co-authored-by: ashwinsom <ashwin.som2001@gmail.com>
Co-authored-by: jai peris <jperis390@gmail.com>
Co-authored-by: danielv012 <daniel@vayman.co>

* Add RRT goal pose: `/planning/goal_pose` (#338)


---------

Co-authored-by: ashwinsom <ashwin.som2001@gmail.com>
Co-authored-by: jai peris <jperis390@gmail.com>
Co-authored-by: danielv012 <daniel@vayman.co>

* Switch to EGMA for cost map (#339)

* Replaced all references to lidar_front/rear to right/left. Parade launch file now contains necessary lidar packages

* subs n pubs

* Filters pointcloud and finds banner x, y

* Create airbag package

* Finish airbags (for now)

* Feature airbags (#340)

* Create airbag package

* Finish airbags (for now)

* Add to rtp

* Double res of route distance

* Basic logic done. TODO: pcl concatenation, I & D terms for PID

* Ready for testing

* Fix right lidar tf

* Parade controller tuning

* Get MCU

* Lidar_front -> Lidar_right transform

* Experiment with Town02 routing

* Added ROS_DOMAIN_ID to leaderboard script

* Add to routes.md

* Add to route generation refinements

* Add Town02 routes for lb testing

* Add rough section

* Add BFS for routing (route not yet generated)

* Can now print route from BFS

* Begin route reorientation/correction

* Route works well enough for now.
- Still crashes sometimes...

* Fix route near/edge indices calculation

* Downsample grids for 4x speedup

* Continue routing refinements

* Re-add map_manager to launch

* Route distance works

* Goal pose publisher re-added

* Finish recurvise tree planner

* Remove costmap debug file

* Add commands to RTP

* Epas, Joy, Linear Actuator ✅

* Forgot this guy

* Route completion now at 31%

* Add airbags (kinda)

* Fixed yaw calculation in map_management

* Further refine RTP

* Add airbag marker

* Add predicted occupancy

* Add junction cost

* Simplify airbags

* pulling form dev

* Fixed prediction framerate

* Add NMEA navsat driver

* Speed up map management grid pub

* Add getBarrierIndex to rtp

* Add barrier marker

* Add barrier braking

* Refine barrier logic

* Add ROS web bridge

* Add barrier penalty

* Boost RTP resolution at root step

* Fix eroson for ego_in_junction

* Publish route progress

* Purge old files

* Rename "grids" to "costs"

* Add junction manager

* Begin joy_translation refactor

* Add center camera

* Add MJPEG camera streaming

* Add Guardian node

* Firmware changes

* Forsook the mode request service
- Replaced with a lame publisher
- Service call hung/froze/blocked

* Updated EPAS & MCU code

* Updated parade launch file, now has lidar drivers

* Add manual control

* Add to Guardian system

* Add camera package

* Add to parade.launch.py

* Move "parade" to "main.launch.py" in root

* Add real-world info to docs

---------

Co-authored-by: ashwinsom <ashwin.som2001@gmail.com>
Co-authored-by: Daniel Vayman <daniel@vayman.co>
Co-authored-by: danielv012 <daniel@vayman.com>
Co-authored-by: Jesse Musa <jessemusa2@gmail.com>
Co-authored-by: jai peris <jperis390@gmail.com>
  • Loading branch information
6 people authored Mar 29, 2023
1 parent 659ccb0 commit 2bac128
Show file tree
Hide file tree
Showing 598 changed files with 25,538 additions and 84,189 deletions.
3 changes: 3 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,13 @@ core
build
install
log
docs/_site
.vscode
.jekyll-cache
*.weights
*.csv
.gitignore
.jekyll-cache
meters_to_gnss_degrees.py
data/maps/grand_loop/carlaMapAdjust3.xodr
data/maps/grand_loop/grand_loop_medium.pcd
Expand Down
19 changes: 14 additions & 5 deletions Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ RUN pip install -v -e . && mim download mmsegmentation --config pspnet_r50-d8_51
# ARG PYTORCH
# ARG CUDA
# ARG MMCV
# RUN pip3 install -U openmim && mim install mmcv-full
RUN pip3 install -U openmim && mim install mmcv-full

# # Install MMSegmentation
# RUN git clone https://github.com/open-mmlab/mmsegmentation.git /mmsegmentation
Expand All @@ -66,13 +66,12 @@ RUN pip install -v -e . && mim download mmsegmentation --config pspnet_r50-d8_51

COPY ./docker/install-dependencies.sh /opt/docker_ws/
RUN apt update && apt install -y software-properties-common && /opt/docker_ws/install-dependencies.sh

COPY ./docker/install-pip-dependencies.sh /opt/docker_ws/
RUN /opt/docker_ws/install-pip-dependencies.sh && rm -rf /var/lib/apt/lists/*

COPY ./docker ./opt/docker_ws

# # Copy and build our modified version of CycloneDDS, important ROS middleware
# Copy and build our modified version of CycloneDDS, important ROS middleware
COPY ./src/tools/cyclonedds /opt/cyclone_ws/cyclonedds
COPY ./src/tools/rmw_cyclonedds /opt/cyclone_ws/rmw_cyclonedds
WORKDIR /opt/cyclone_ws
Expand All @@ -85,13 +84,17 @@ RUN apt update && echo "net.core.rmem_max=8388608\nnet.core.rmem_default=8388608
#################
# Code here should either be moved to install-dependencies.sh or removed
# before each major release.
RUN apt update && apt install -y ros-foxy-octomap octovis ros-foxy-pcl-ros ros-foxy-tf2-eigen
#RUN apt update && apt install -y ros-foxy-octomap octovis ros-foxy-pcl-ros ros-foxy-tf2-eigen
RUN pip3 install shapely==2.0.0

RUN pip3 install --upgrade scipy networkx
RUN pip3 install --upgrade scipy networkx

# https://stackoverflow.com/questions/66669735/ubuntu-20-04-cant-find-pcl-because-of-incorrect-include-directory-after-install
RUN mkdir /lib/x86_64-linux-gnu/cmake/pcl/include && ln -s /usr/include/pcl-1.10/pcl /lib/x86_64-linux-gnu/cmake/pcl/include/pcl

RUN apt update && apt install -y ros-foxy-joy-linux ros-foxy-pcl-ros minicom ros-foxy-rosbridge-server ros-foxy-image-transport ros-foxy-async-web-server-cpp

RUN pip3 install scikit-image
#################
# END CLEANUP #
#################
Expand All @@ -100,4 +103,10 @@ ENV ROS_VERSION 2

WORKDIR /navigator
COPY ./docker/entrypoint.sh /opt/entrypoint.sh

# RUN useradd -ms /bin/bash docker
RUN usermod -a -G dialout root
RUN usermod -a -G tty root
# USER docker

ENTRYPOINT [ "/opt/entrypoint.sh" ]
4 changes: 2 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
[<img src="docs/assets/res/logo.png" width="600" />](https://nova-utd.github.io/navigator)
[<img src="docs/assets/res/logo-alt.gif" width="200" />](https://nova-utd.github.io/navigator)

Navigator is a simple, modular, open-source autonomous driving stack. It's developed by Nova, an undergraduate research team at UT Dallas.

For docs, visit [our documentation site](https://nova-utd.github.io/navigator).

For info about our group, Nova, visit our [group site](https://nova-utd.github.io).
For info about our group, Nova, visit our [group site](https://nova-utd.github.io).
Binary file removed data/carla-0.9.13-py3.7-linux-x86_64.egg
Binary file not shown.
2 changes: 1 addition & 1 deletion data/carla.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
<geometry>
<box size="4.37 2.0 1.85" />
</geometry>
<origin xyz="-1.7 0 0.645" rpy="0 0 0" />
<origin xyz="-0.7 0 0.645" rpy="0 0 0" />
</collision>
</link>
<link name="hero"/>
Expand Down
44 changes: 28 additions & 16 deletions data/carla_objects.json
Original file line number Diff line number Diff line change
Expand Up @@ -9,32 +9,37 @@
{
"type": "vehicle.tesla.model3",
"id": "hero",
"spawn_point": {"x": 17.8, "y": -192.0, "z": 1.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
"spawn_point": {"x": 21.7, "y": -191.9, "z": 1.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
"sensors":
[
{
"type": "sensor.camera.rgb",
"id": "birds_eye",
"spawn_point": {"x": 0.85, "y": 0.0, "z": 25.0, "roll": 0.0, "pitch": 90.0, "yaw": 0.0},
"image_size_x": 1024,
"image_size_y": 512,
"fov": 120.0
"type": "sensor.pseudo.tf",
"id": "tf",
"spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}
},
{
"type": "sensor.camera.rgb",
"id": "rgb_left",
"spawn_point": {"x": 0.7, "y": 0.15, "z": 1.88, "roll": 0.0, "pitch": 0.0, "yaw": 60.0},
"image_size_x": 1024,
"image_size_y": 512,
"fov": 120.0
"spawn_point": {"x": 0.7, "y": 0.15, "z": 1.88, "roll": 0.0, "pitch": 0.0, "yaw": 70.0},
"image_size_x": 800,
"image_size_y": 600,
"fov": 70.0
},
{
"type": "sensor.camera.rgb",
"id": "rgb_center",
"spawn_point": {"x": 0.7, "y": -0.15, "z": 1.88, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
"image_size_x": 800,
"image_size_y": 600,
"fov": 70.0
},
{
"type": "sensor.camera.rgb",
"id": "rgb_right",
"spawn_point": {"x": 0.7, "y": -0.15, "z": 1.88, "roll": 0.0, "pitch": 0.0, "yaw": -60.0},
"image_size_x": 1024,
"image_size_y": 512,
"fov": 120.0
"spawn_point": {"x": 0.7, "y": -0.15, "z": 1.88, "roll": 0.0, "pitch": 0.0, "yaw": -70.0},
"image_size_x": 800,
"image_size_y": 600,
"fov": 70.0
},
{
"type": "sensor.lidar.ray_cast",
Expand Down Expand Up @@ -70,10 +75,17 @@
"noise_alt_stddev": 0.000005, "noise_lat_stddev": 0.000005, "noise_lon_stddev": 0.000005,
"noise_alt_bias": 0.0, "noise_lat_bias": 0.0, "noise_lon_bias": 0.0
},
{
"type": "sensor.other.gnss",
"id": "true_gnss",
"spawn_point": {"x": 0.0, "y": 0.0, "z": 0.00},
"noise_alt_stddev": 0.0, "noise_lat_stddev": 0.0, "noise_lon_stddev": 0.0,
"noise_alt_bias": 0.0, "noise_lat_bias": 0.0, "noise_lon_bias": 0.0
},
{
"type": "sensor.other.imu",
"id": "imu",
"spawn_point": {"x": 0.7, "y": 0.0, "z": 0.28, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
"spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
"noise_accel_stddev_x": 0.001, "noise_accel_stddev_y": 0.001, "noise_accel_stddev_z": 0.015,
"noise_gyro_stddev_x": 0.001, "noise_gyro_stddev_y": 0.001, "noise_gyro_stddev_z": 0.001,
"noise_gyro_bias_x": 0.0, "noise_gyro_bias_y": 0.0, "noise_gyro_bias_z": 0.0
Expand Down
71 changes: 71 additions & 0 deletions data/fastrtps.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
<?xml version="1.0" encoding="UTF-8"?>
<dds xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles">
<profiles>

<transport_descriptors>
<transport_descriptor>
<transport_id>test</transport_id>
<type>UDPv4</type>
<maxMessageSize>5500</maxMessageSize>
<non_blocking_send>true</non_blocking_send>
</transport_descriptor>
</transport_descriptors>

<participant profile_name="participant profile" is_default_profile="true">
<rtps>
<userTransports>
<transport_id>test</transport_id>
</userTransports>
<useBuiltinTransports>false</useBuiltinTransports>
</rtps>
</participant>

<!-- Default publisher profile -->
<publisher profile_name="default publisher profile" is_default_profile="true">
<qos>
<publishMode>
<kind>SYNCHRONOUS</kind>
</publishMode>
</qos>
<historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy>
</publisher>

<!-- Default subscriber profile -->
<subscriber profile_name="default subscriber profile" is_default_profile="true">
<historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy>
</subscriber>

<!-- Publisher profile for topic helloworld -->
<publisher profile_name="helloworld">
<qos>
<publishMode>
<kind>SYNCHRONOUS</kind>
</publishMode>
</qos>
</publisher>

<!-- Request subscriber profile for services -->
<subscriber profile_name="service">
<historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy>
</subscriber>

<!-- Request publisher profile for clients -->
<publisher profile_name="client">
<qos>
<publishMode>
<kind>ASYNCHRONOUS</kind>
</publishMode>
</qos>
</publisher>

<!-- Request subscriber profile for server of service "add_two_ints" -->
<subscriber profile_name="rq/add_two_intsRequest">
<historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy>
</subscriber>

<!-- Reply subscriber profile for client of service "add_two_ints" -->
<subscriber profile_name="rr/add_two_intsReply">
<historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy>
</subscriber>
</profiles>
</dds>
14 changes: 7 additions & 7 deletions data/hail_bopp.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@
<origin xyz="0.0 -0.5 0.5" rpy="0 0 0"/>
</joint>

<link name="lidar_front">
<link name="lidar_right">
<visual>
<geometry>
<cylinder length="0.0869" radius="0.05165"/>
Expand All @@ -89,13 +89,13 @@
</inertial>
</link>

<joint name="lidar_front_joint" type="fixed">
<joint name="lidar_right_joint" type="fixed">
<parent link="base_link"/>
<child link="lidar_front"/>
<origin xyz="0.0 -0.902 0.7876" rpy="-0.015 -0.03 -1.45"/>
<child link="lidar_right"/>
<origin xyz="-0.6096 -0.7366 1.8748" rpy="-.20 .20 -.95"/>
</joint>

<link name="lidar_rear">
<link name="lidar_left">
<visual>
<geometry>
<cylinder length="0.0869" radius="0.05165"/>
Expand All @@ -114,9 +114,9 @@
</inertial>
</link>

<joint name="lidar_rear_joint" type="fixed">
<joint name="lidar_left_joint" type="fixed">
<parent link="base_link"/>
<child link="lidar_rear"/>
<child link="lidar_left"/>
<origin xyz="-3.5 0.9 1.1" rpy="+0.03 -0.0472 2.65"/>
</joint>

Expand Down
File renamed without changes.
Loading

0 comments on commit 2bac128

Please sign in to comment.