Skip to content

Commit 81681fa

Browse files
committed
Merge branch 'main' into testing-calibrate-field-coordinates
2 parents 924ded2 + d56eb3f commit 81681fa

18 files changed

Lines changed: 340 additions & 58 deletions

File tree

arduino/sensors/sensors.ino

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -13,8 +13,8 @@ struct SensorData {
1313
#define DIGGER_BOTTOM_LIMIT_SWITCH 3
1414
#define DUMPER_TOP_LIMIT_SWITCH 4
1515
#define DUMPER_BOTTOM_LIMIT_SWITCH 5
16-
#define LEFT_MOTOR_POT_PIN A0
17-
#define RIGHT_MOTOR_POT_PIN A1
16+
#define LEFT_MOTOR_POT_PIN A2
17+
#define RIGHT_MOTOR_POT_PIN A3
1818

1919
void setup() {
2020
// Initialize serial communication

config/motor_control.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,5 +19,5 @@
1919
DIGGER_SAFETY_ZONE: 120 # Measured in potentiometer units (0 to 1023)
2020
CURRENT_SPIKE_THRESHOLD: 1.8 # Threshold for current spike detection (measured in Amps)
2121
CURRENT_SPIKE_TIME: 0.2 # Time in seconds to consider it a current spike (measured in seconds)
22-
BUCKETS_CURRENT_SPIKE_THRESHOLD: 8.0 # Threshold for current spike detection (measured in Amps)
22+
BUCKETS_CURRENT_SPIKE_THRESHOLD: 10.0 # Threshold for current spike detection (measured in Amps)
2323
BUCKETS_CURRENT_SPIKE_TIME: 0.2 # Time in seconds to consider it a current spike (measured in seconds)

config/nav2_isaac_sim.yaml

Lines changed: 5 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,6 @@ bt_navigator:
2828
- nav2_follow_path_action_bt_node
2929
- nav2_spin_action_bt_node
3030
- nav2_wait_action_bt_node
31-
- nav2_assisted_teleop_action_bt_node
3231
- nav2_back_up_action_bt_node
3332
- nav2_drive_on_heading_bt_node
3433
- nav2_clear_costmap_service_bt_node
@@ -54,7 +53,6 @@ bt_navigator:
5453
- nav2_distance_traveled_condition_bt_node
5554
- nav2_single_trigger_bt_node
5655
- nav2_goal_updated_controller_bt_node
57-
- nav2_is_battery_low_condition_bt_node
5856
- nav2_navigate_through_poses_action_bt_node
5957
- nav2_navigate_to_pose_action_bt_node
6058
- nav2_remove_passed_goals_action_bt_node
@@ -66,9 +64,7 @@ bt_navigator:
6664
- nav2_wait_cancel_bt_node
6765
- nav2_spin_cancel_bt_node
6866
- nav2_back_up_cancel_bt_node
69-
- nav2_assisted_teleop_cancel_bt_node
7067
- nav2_drive_on_heading_cancel_bt_node
71-
- nav2_is_battery_charging_condition_bt_node
7268
bt_navigator_navigate_through_poses_rclcpp_node:
7369
ros__parameters:
7470
use_sim_time: False
@@ -295,8 +291,7 @@ behavior_server:
295291
costmap_topic: local_costmap/costmap_raw
296292
footprint_topic: local_costmap/published_footprint
297293
cycle_frequency: 10.0
298-
behavior_plugins:
299-
["spin", "backup", "drive_on_heading", "assisted_teleop", "wait"]
294+
behavior_plugins: ["spin", "backup", "drive_on_heading", "wait"]
300295
spin:
301296
plugin: "nav2_behaviors/Spin"
302297
backup:
@@ -305,16 +300,14 @@ behavior_server:
305300
plugin: "nav2_behaviors/DriveOnHeading"
306301
wait:
307302
plugin: "nav2_behaviors/Wait"
308-
assisted_teleop:
309-
plugin: "nav2_behaviors/AssistedTeleop"
310303
global_frame: odom
311304
robot_base_frame: base_link
312305
transform_tolerance: 0.1
313306
use_sim_time: False
314-
simulate_ahead_time: 2.0
315-
max_rotational_vel: 1.0
316-
min_rotational_vel: 0.4
317-
rotational_acc_lim: 3.2
307+
simulate_ahead_time: 1.0
308+
max_rotational_vel: 0.75
309+
min_rotational_vel: -0.75
310+
rotational_acc_lim: 0.75
318311

319312
robot_state_publisher:
320313
ros__parameters:

config/rovr_control.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
ros__parameters:
33
max_drive_power: 1.0 # Measured in Duty Cycle (0.0-1.0)
44
max_turn_power: 1.0 # Measured in Duty Cycle (0.0-1.0)
5-
digger_chain_power: 0.2 # Measured in Duty Cycle (0.0-1.0)
5+
digger_chain_power: 0.18 # Measured in Duty Cycle (0.0-1.0)
66
digger_lift_manual_power_down: 0.12 # Measured in Duty Cycle (0.0-1.0)
77
digger_lift_manual_power_up: 0.5 # Measured in Duty Cycle (0.0-1.0)
88
autonomous_field_type: "cosmic" # The type of field ("cosmic", "top", "bottom", "nasa")

config/sensors/zed_common.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -64,7 +64,7 @@
6464

6565
pos_tracking:
6666
pos_tracking_enabled: true # True to enable positional tracking from start
67-
pos_tracking_mode: "GEN_2" # Matches the ZED SDK setting: 'GEN_1', 'GEN_2'
67+
pos_tracking_mode: "GEN_1" # Matches the ZED SDK setting: 'GEN_1', 'GEN_2'
6868
imu_fusion: true # enable/disable IMU fusion. When set to false, only the optical odometry will be used.
6969
publish_tf: true # [usually overwritten by launch file] publish `odom -> camera_link` TF
7070
publish_map_tf: false # [usually overwritten by launch file] publish `map -> odom` TF

scripts/laptop.sh

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
11
#!/bin/bash
22

33
source install/setup.bash && \
4-
ros2 launch gstreamer laptop_launch.py
4+
ros2 run rqt_image_view rqt_image_view

src/isaac_ros/isaac_ros_launch/launch/EVERYTHING_launch.py

Lines changed: 6 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,5 @@
11
from launch_ros.substitutions import FindPackageShare
22

3-
from launch_ros.actions import Node
43
from launch import LaunchDescription
54
from launch.actions import IncludeLaunchDescription
65
from launch.launch_description_sources import PythonLaunchDescriptionSource
@@ -21,26 +20,23 @@ def generate_launch_description():
2120
launch_arguments={
2221
"setup_for_zed": "True",
2322
"setup_for_gazebo": "False",
24-
"use_nvblox": "True",
23+
"use_nvblox": "False",
2524
"use_nav2": "True",
2625
"run_rviz_robot": "False", # We don't need to run RViz during matches
2726
"zed_multicam": "True", # Use multiple ZED cameras
28-
"record_svo": "False", # TODO: Change this back before merging (False for testing only)
27+
"record_svo": "True", # Record match data to an SVO file
28+
"use_apriltags": "False",
2929
}.items(),
3030
)
3131

32-
gstreamer_server = Node(
33-
package="gstreamer",
34-
executable="server_node",
35-
name="gstreamer_server_node",
36-
output="screen",
37-
emulate_tty=True,
32+
camera_launch = IncludeLaunchDescription(
33+
PythonLaunchDescriptionSource(PathJoinSubstitution([FindPackageShare("rovr_control"), "camera_launch.py"]))
3834
)
3935

4036
# Add all of the actions to the launch description
4137
ld.add_action(main_launch)
42-
# ld.add_action(gstreamer_server) # TODO: Change this back before merging (commmented for testing only)
4338
ld.add_action(isaac_launch)
39+
ld.add_action(camera_launch)
4440

4541
# Return the launch description
4642
return ld

src/isaac_ros/isaac_ros_launch/launch/isaac_launch.py

Lines changed: 11 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@
55
DeclareLaunchArgument,
66
IncludeLaunchDescription,
77
)
8-
from launch.conditions import IfCondition, UnlessCondition
8+
from launch.conditions import IfCondition
99
from launch.launch_description_sources import PythonLaunchDescriptionSource
1010
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution, PythonExpression
1111
from nav2_common.launch import RewrittenYaml
@@ -17,6 +17,8 @@ def generate_launch_description():
1717
setup_for_zed = LaunchConfiguration("setup_for_zed", default="True")
1818
use_nvblox = LaunchConfiguration("use_nvblox", default="True")
1919
zed_multicam = LaunchConfiguration("zed_multicam", default="False")
20+
use_apriltags = LaunchConfiguration("use_apriltags", default="True")
21+
setup_for_gazebo = LaunchConfiguration("setup_for_gazebo", default="False")
2022

2123
# Launch Arguments
2224
run_rviz_arg = DeclareLaunchArgument("run_rviz_robot", default_value="True", description="Whether to start RVIZ")
@@ -55,6 +57,11 @@ def generate_launch_description():
5557
default_value="False",
5658
description="Whether to use two ZED cameras",
5759
)
60+
use_apriltags_arg = DeclareLaunchArgument(
61+
"use_apriltags",
62+
default_value="True",
63+
description="Whether to run isaac ros apriltags",
64+
)
5865

5966
global_frame = LaunchConfiguration("global_frame", default="odom")
6067

@@ -161,14 +168,14 @@ def generate_launch_description():
161168
# apriltag launch
162169
apriltag_launch = IncludeLaunchDescription(
163170
PythonLaunchDescriptionSource([PathJoinSubstitution([FindPackageShare("apriltag"), "apriltag_launch.py"])]),
164-
condition=UnlessCondition(LaunchConfiguration("setup_for_gazebo")),
171+
condition=IfCondition(PythonExpression([use_apriltags, " and not ", setup_for_gazebo])),
165172
)
166173
# apriltag (gazebo) launch
167174
apriltag_gazebo_launch = IncludeLaunchDescription(
168175
PythonLaunchDescriptionSource(
169176
[PathJoinSubstitution([FindPackageShare("apriltag"), "apriltag_gazebo_launch.py"])]
170177
),
171-
condition=IfCondition(LaunchConfiguration("setup_for_gazebo")),
178+
condition=IfCondition(PythonExpression([use_apriltags, " and ", setup_for_gazebo])),
172179
)
173180

174181
return LaunchDescription(
@@ -180,6 +187,7 @@ def generate_launch_description():
180187
use_nvblox_arg,
181188
use_nav2_arg,
182189
zed_multicam_arg,
190+
use_apriltags_arg,
183191
shared_container,
184192
nvblox_launch,
185193
nvblox_multicam_launch,

src/motor_control/src/motor_control_node.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -490,15 +490,15 @@ class MotorControlNode : public rclcpp::Node {
490490
// Log an error message
491491
RCLCPP_ERROR(this->get_logger(), "ERROR: Position difference between linear actuators is too high! Stopping both motors.");
492492
}
493-
else if ((msg.left_motor_pot == 1023) || (msg.right_motor_pot == 1023)) {
493+
else if ((msg.left_motor_pot >= 1023) || (msg.right_motor_pot >= 1023)) {
494494
// Stop both motors!
495495
this->digger_lift_goal = { "duty_cycle", 0.0 };
496496
vesc_set_duty_cycle(this->get_parameter("DIGGER_LEFT_LINEAR_ACTUATOR").as_int(), 0.0);
497497
vesc_set_duty_cycle(this->get_parameter("DIGGER_RIGHT_LINEAR_ACTUATOR").as_int(), 0.0);
498498
// Log an error message
499499
RCLCPP_ERROR(this->get_logger(), "ERROR: Potentiometer has reached max value! Stopping both motors, check if one is unplugged");
500500
}
501-
else if ((msg.left_motor_pot == 0) || (msg.right_motor_pot == 0)) {
501+
else if ((msg.left_motor_pot <= 0) || (msg.right_motor_pot <= 0)) {
502502
// Stop both motors!
503503
this->digger_lift_goal = { "duty_cycle", 0.0 };
504504
vesc_set_duty_cycle(this->get_parameter("DIGGER_LEFT_LINEAR_ACTUATOR").as_int(), 0.0);
Lines changed: 41 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,41 @@
1+
from launch import LaunchDescription
2+
from launch_ros.actions import Node
3+
4+
5+
def generate_camera_nodes(camera_name, video_device, resolution=(640, 480), quality=60):
6+
return [
7+
# Camera driver node
8+
Node(
9+
package="v4l2_camera",
10+
executable="v4l2_camera_node",
11+
namespace=camera_name,
12+
name="camera",
13+
parameters=[
14+
{"video_device": video_device},
15+
{"image_size": [resolution[0], resolution[1]]},
16+
{"pixel_format": "YUYV"},
17+
{".image_raw.jpeg_quality": quality},
18+
],
19+
remappings=[("/image_raw", "image_raw"), ("/camera_info", "camera_info")], # scoped to namespace
20+
),
21+
# Compressed republisher
22+
Node(
23+
package="image_transport",
24+
executable="republish",
25+
namespace=camera_name,
26+
name="republish_compressed",
27+
arguments=["raw", "compressed"],
28+
remappings=[("in", f"{video_device}/image_raw"), ("out", "image_raw/compressed")],
29+
),
30+
]
31+
32+
33+
def generate_launch_description():
34+
return LaunchDescription(
35+
generate_camera_nodes("left", "/dev/video4", (1280, 720), quality=60)
36+
# + generate_camera_nodes('back', '/dev/video0')
37+
# + generate_camera_nodes('left', '/dev/video0')
38+
# + generate_camera_nodes('right', '/dev/video0')
39+
# + generate_camera_nodes('dumper', '/dev/video0')
40+
# + generate_camera_nodes('digger', '/dev/video0')
41+
)

0 commit comments

Comments
 (0)