Skip to content

Commit

Permalink
pulled integration
Browse files Browse the repository at this point in the history
  • Loading branch information
neuenfeldttj committed Apr 29, 2024
2 parents 5b09907 + 032f3b7 commit e42a1f3
Show file tree
Hide file tree
Showing 93 changed files with 2,070 additions and 881 deletions.
14 changes: 11 additions & 3 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -67,15 +67,19 @@ set(MROVER_ROS_DEPENDENCIES
tf2
tf2_ros
tf2_geometry_msgs
actionlib_msgs
)

extract_filenames(msg/*.msg MROVER_MESSAGE_FILES)

extract_filenames(srv/*.srv MROVER_SERVICE_FILES)

extract_filenames(action/*.action MROVER_ACTION_FILES)

set(MROVER_MESSAGE_DEPENDENCIES
std_msgs
sensor_msgs
actionlib_msgs
)

set(MROVER_PARAMETERS
Expand Down Expand Up @@ -123,6 +127,8 @@ add_message_files(FILES ${MROVER_MESSAGE_FILES})

add_service_files(FILES ${MROVER_SERVICE_FILES})

add_action_files(DIRECTORY action FILES ${MROVER_ACTION_FILES})

generate_messages(DEPENDENCIES ${MROVER_MESSAGE_DEPENDENCIES})

generate_dynamic_reconfigure_options(${MROVER_PARAMETERS})
Expand Down Expand Up @@ -197,9 +203,11 @@ if (CUDA_FOUND)
# target_include_directories(nv_vid_codec_h265_enc SYSTEM PUBLIC deps/nvenc)
endif ()

mrover_add_nodelet(gst_websocket_streamer src/esw/gst_websocket_streamer/*.c* src/esw/gst_websocket_streamer src/esw/gst_websocket_streamer/pch.hpp)
mrover_nodelet_link_libraries(gst_websocket_streamer PRIVATE websocket_server ${Gst_LIBRARIES} ${GstApp_LIBRARIES})
mrover_nodelet_include_directories(gst_websocket_streamer ${Gst_INCLUDE_DIRS} ${GstApp_INCLUDE_DIRS})
if (Gst_FOUND AND GstApp_FOUND AND LibUsb_FOUND AND LibUdev_FOUND)
mrover_add_nodelet(gst_websocket_streamer src/esw/gst_websocket_streamer/*.c* src/esw/gst_websocket_streamer src/esw/gst_websocket_streamer/pch.hpp)
mrover_nodelet_link_libraries(gst_websocket_streamer PRIVATE websocket_server ${Gst_LIBRARIES} ${GstApp_LIBRARIES} ${LibUsb_LIBRARIES} ${LibUdev_LIBRARIES} opencv_core opencv_imgproc)
mrover_nodelet_include_directories(gst_websocket_streamer ${Gst_INCLUDE_DIRS} ${GstApp_INCLUDE_DIRS} ${LibUsb_INCLUDE_DIRS} ${LibUdev_INCLUDE_DIRS})
endif ()

if (ZED_FOUND)
mrover_add_nodelet(object_detector src/perception/object_detector/*.c* src/perception/object_detector src/perception/object_detector/pch.hpp)
Expand Down
3 changes: 3 additions & 0 deletions action/ArmAction.action
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
string name
---
---
1 change: 1 addition & 0 deletions ansible/roles/build/tasks/main.yml
Original file line number Diff line number Diff line change
Expand Up @@ -97,6 +97,7 @@
- libgstreamer1.0-dev
- libgstreamer-plugins-base1.0-dev
- vainfo
- x264

- name: Install Local APT Packages
become: True
Expand Down
2 changes: 1 addition & 1 deletion ansible/roles/esw/tasks/main.yml
Original file line number Diff line number Diff line change
Expand Up @@ -22,4 +22,4 @@

- name: Install Moteus GUI
pip:
name: moteus_gui
name: moteus-gui
6 changes: 6 additions & 0 deletions ansible/roles/jetson_services/files/rules/99-usb-serial.rules
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
SUBSYSTEM=="tty", ATTRS{idVendor}=="1546", ATTRS{idProduct}=="01a9", SYMLINK+="gps_%n"
SUBSYSTEM=="tty", ATTRS{idVendor}=="2341", ATTRS{idProduct}=="0058", SYMLINK+="imu"
SUBSYSTEM=="video4linux", KERNEL=="video*", ATTRS{idVendor}=="1bcf", ATTRS{idProduct}=="0b12", ATTR{index}=="0", GROUP="video", SYMLINK+="arducam"
SUBSYSTEM=="video4linux", KERNEL=="video*", ATTRS{idVendor}=="2b03", ATTRS{idProduct}=="f582", ATTR{index}=="0", GROUP="video", SYMLINK+="zed"
SUBSYSTEM=="video4linux", KERNEL=="video*", ATTRS{idVendor}=="05a3", ATTRS{idProduct}=="9601", ATTR{index}=="0", GROUP="video", SYMLINK+="mobcam"
SUBSYSTEM=="video4linux", KERNEL=="video*", ATTRS{idVendor}=="32e4", ATTRS{idProduct}=="9601", ATTR{index}=="0", GROUP="video", SYMLINK+="staticcam"
14 changes: 14 additions & 0 deletions ansible/roles/jetson_services/tasks/main.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
- name: USB Rules
become: true
synchronize:
src: files/rules/
dest: /etc/udev/rules.d
recursive: true

- name: udev Reload Rules
become: true
command: udevadm control --reload-rules

- name: udev TTY Trigger
become: true
command: udevadm trigger --subsystem-match=tty
2 changes: 2 additions & 0 deletions cmake/deps.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -69,3 +69,5 @@ pkg_search_module(NetLink libnl-3.0 QUIET)
pkg_search_module(NetLinkRoute libnl-route-3.0 QUIET)
pkg_search_module(Gst gstreamer-1.0 QUIET)
pkg_search_module(GstApp gstreamer-app-1.0 QUIET)
pkg_search_module(LibUsb libusb-1.0 QUIET)
pkg_search_module(LibUdev libudev QUIET)
35 changes: 22 additions & 13 deletions config/esw.yaml
Original file line number Diff line number Diff line change
@@ -1,14 +1,23 @@
right_gps_driver:
port: "/dev/ttyACM0"
baud: 38400
frame_id: "base_link"

left_gps_driver:
port: "/dev/gps"
baud: 38400
frame_id: "base_link"

basestation_gps_driver:
port: "/dev/gps"
baud: 38400
frame_id: "base_link"

imu_driver:
port: "/dev/imu"
baud: 115200
frame_id: "imu_link"

gps:
port: "/dev/gps"
baud: 115200
useRMC: false # get covariance instead of velocity, see wiki for more info
frame_id: "base_link"

can:
devices:
- name: "jetson"
Expand Down Expand Up @@ -43,7 +52,7 @@ can:
id: 0x15
- name: "joint_a"
bus: 1
id: 0x20
id: 0x20
- name: "joint_b"
bus: 1
id: 0x21
Expand All @@ -64,10 +73,10 @@ can:
id: 0x26
- name: "mast_gimbal_y"
bus: 3
id: 0x28
id: 0x27
- name: "mast_gimbal_z"
bus: 3
id: 0x27
id: 0x28
- name: "sa_x"
bus: 1
id: 0x29
Expand Down Expand Up @@ -144,11 +153,11 @@ brushless_motors:
max_backward_pos: 0.0
max_torque: 20.0
joint_c:
min_velocity: -0.04 # in terms of output
max_velocity: 0.04 # max output shaft speed: 5 rpm (for now)
min_velocity: -0.03 # in terms of output
max_velocity: 0.03 # max output shaft speed: 5 rpm (for now)
min_position: -0.125
max_position: 0.30 # 220 degrees of motion is the entire range
max_torque: 20.0
max_torque: 200.0
joint_de_0:
min_velocity: -5.0
max_velocity: 5.0
Expand Down Expand Up @@ -591,7 +600,7 @@ motors:
default_network_iface: "enp0s31f6"

auton_led_driver:
port: "/dev/ttyACM0"
port: "/dev/led"
baud: 115200

science:
Expand Down
1 change: 1 addition & 0 deletions config/localization.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -8,3 +8,4 @@ gps_linearization:
reference_point_longitude: -83.7096706
reference_point_altitude: 234.1
reference_heading: 90.0
use_both_gps: false
4 changes: 2 additions & 2 deletions config/moteus/joint_c.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -1363,9 +1363,9 @@ servo.adc_cur_cycles 2
servo.adc_aux_cycles 47
servo.pid_dq.kp 0.060606
servo.pid_dq.ki 102.321388
servo.pid_position.kp 14.000000
servo.pid_position.kp 800.000000
servo.pid_position.ki 0.000000
servo.pid_position.kd 1.450000
servo.pid_position.kd 50.000000
servo.pid_position.iratelimit -1.000000
servo.pid_position.ilimit 0.000000
servo.pid_position.max_desired_rate 0.000000
Expand Down
49 changes: 26 additions & 23 deletions config/teleop.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -6,34 +6,24 @@ teleop:
joint_a:
multiplier: -1
slow_mode_multiplier: 0.5
invert: True
xbox_index: 0
joint_b:
multiplier: 1
slow_mode_multiplier: 1
invert: False
xbox_index: 1
joint_c:
multiplier: -1
multiplier: 1
slow_mode_multiplier: 0.6
invert: False
xbox_index: 3
joint_de_pitch:
multiplier: 0.5
multiplier: -1
slow_mode_multiplier: 1
invert: True
joint_de_roll:
multiplier: -0.5
multiplier: 1
slow_mode_multiplier: 1
invert: True
allen_key:
multiplier: 1
slow_mode_multiplier: 1
invert: False
gripper:
multiplier: 1
slow_mode_multiplier: 1
invert: True

sa_controls:
sa_x:
Expand Down Expand Up @@ -67,21 +57,34 @@ teleop:
enabled: true
multiplier: 1
twist:
multiplier: 0.7
multiplier: 0.6
tilt:
multiplier: 1
pan:
multiplier: 1

xbox_mappings:
left_js_x: 0
left_js_y: 1
right_js_x: 2
right_js_y: 3
left_trigger: 6
right_trigger: 7
left_x: 0
left_y: 1
right_x: 2
right_y: 3
a: 0
b: 1
x: 2
y: 3
left_bumper: 4
right_bumper: 5
left_trigger: 6
right_trigger: 7
back: 8
forward: 9
left_stick_click: 10
right_stick_click: 11
dpad_up: 12
dpad_down: 13
dpad_left: 14
dpad_right: 15
home: 16

joystick_mappings:
left_right: 0
Expand Down Expand Up @@ -119,9 +122,9 @@ teleop:
bar: ["/tf_static", "/rosout", "/tf"]

ik_multipliers:
x: 1
y: 1
z: 1
x: 0.1
y: 0.1
z: 0.1

cameras:
- name: "ZED"
Expand Down
2 changes: 1 addition & 1 deletion launch/autonomy.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<arg name="run_object_detector" default="false" />

<arg name="sim" default="false" />
<arg name="use_ekf" default="true" />
<arg name="use_ekf" default="false" />
<arg name="ekf_start_delay" default="0" />

<include file="$(find mrover)/launch/perception.launch">
Expand Down
13 changes: 10 additions & 3 deletions launch/basestation.launch
Original file line number Diff line number Diff line change
Expand Up @@ -4,21 +4,28 @@
<launch>
<arg name="run_rviz" default="false" />
<arg name="run_network_monitor" default="false" />
<arg name="run_backend" default="true" />
<arg name="run_frontend" default="true" />
<arg name="run_browser" default="true" />
<arg name="rtk" default="true" />

<rosparam command="load" file="$(find mrover)/config/esw.yaml" />
<rosparam command="load" file="$(find mrover)/config/teleop.yaml" />
<rosparam command="load" file="$(find mrover)/config/localization.yaml" />

<node name="gui_frontend" pkg="mrover" type="gui_frontend.sh" cwd="node" required="true" />
<node name="gui_backend" pkg="mrover" type="gui_backend.sh" cwd="node" required="true" />
<node name="gui_chromium" pkg="mrover" type="gui_chromium.sh" />
<node if="$(arg run_frontend)" name="gui_frontend" pkg="mrover" type="gui_frontend.sh" cwd="node" required="true" />
<node if="$(arg run_backend)" name="gui_backend" pkg="mrover" type="gui_backend.sh" cwd="node" required="true" />
<node if="$(arg run_browser)" name="gui_chromium_menu" pkg="mrover" type="gui_chromium_menu.sh" />
<node if="$(arg run_browser)" name="gui_chromium_cameras" pkg="mrover" type="gui_chromium_cameras.sh" />

<group if="$(arg run_rviz)">
<arg name="rvizconfig" default="$(find mrover)/config/rviz/basestation.rviz" />
<node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)" />
<node name="topic_services" pkg="mrover" type="topic_services.py" />
</group>

<include if="$(arg rtk)" file="$(find mrover)/launch/rtk_basestation.launch" />

<!-- network monitor node-->
<node if="$(arg run_network_monitor)"
name="network_monitor" pkg="mrover" type="network_monitor.py" />
Expand Down
Loading

0 comments on commit e42a1f3

Please sign in to comment.