Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Try fix lidar port #273

Merged
merged 15 commits into from
Apr 18, 2023
38 changes: 13 additions & 25 deletions mep3_behavior/strategies/big_blue.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,26 +2,19 @@
<root BTCPP_format="4">
<BehaviorTree ID="big_blue">
<SequenceWithMemory>
<WaitMatchStart state="2"/>
<Fallback>
<Move goal="0.4;0.4;0"
ignore_obstacles="false"
max_acceleration="0.5"
max_velocity="1.0"/>
<Repeat num_cycles="6">
<Sequence>
<Wait duration="0.5"/>
<Move goal="0.58;-0.43;0"
ignore_obstacles="false"
max_acceleration="0.5"
max_velocity="1.0"/>
</Sequence>
</Repeat>
<Move goal="0.4;0.4;0"
ignore_obstacles="false"
max_acceleration="0.5"
max_velocity="1.0"/>
</Fallback>
<Wait duration="3"/>
<Move goal="0.4;0.4;0"
ignore_obstacles="false"
max_acceleration="0.5"
max_velocity="0.8"/>
<Move goal="0;0;0"
ignore_obstacles="false"
max_acceleration="0.5"
max_velocity="1.0"/>
<Move goal="0.4;0.4;0"
ignore_obstacles="false"
max_acceleration="0.5"
max_velocity="0.8"/>
</SequenceWithMemory>
</BehaviorTree>

Expand All @@ -41,11 +34,6 @@
editable="true">
<input_port name="duration"/>
</Action>
<Action ID="WaitMatchStart"
editable="false">
<input_port name="state"
default="2">0 = unarmed; 1 = armed; 2 = started</input_port>
</Action>
</TreeNodesModel>

</root>
6 changes: 4 additions & 2 deletions mep3_hardware/launch/hardware_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,8 @@ def launch_setup(context, *args, **kwargs):
namespace = LaunchConfiguration('namespace', default='big')
performed_namespace = namespace.perform(context)

usb_port = '/dev/serial/by-id/usb-Silicon_Labs_CP2102_USB_to_UART_Bridge_9e82eec869f4c84fb1901fc50d00c93c-if00-port0' if performed_namespace == 'big' else '/dev/serial/by-id/usb-Silicon_Labs_CP2102_USB_to_UART_Bridge_0e10a6d7001d8f4fad5376bfd2f6f1ad-if00-port0'

controller_params_file = os.path.join(package_dir, 'resource', f'{performed_namespace}_controllers.yaml')
robot_description = pathlib.Path(os.path.join(package_dir, 'resource', f'{performed_namespace}_description.urdf')).read_text()

Expand Down Expand Up @@ -75,7 +77,7 @@ def launch_setup(context, *args, **kwargs):
name='rplidar_ros',
parameters=[{
'frame_id': 'laser',
'serial_port': '/dev/serial/by-id/usb-Silicon_Labs_CP2102_USB_to_UART_Bridge_9e82eec869f4c84fb1901fc50d00c93c-if00-port0'
'serial_port': usb_port
}],
ros_arguments=['--log-level', 'warn'],
output='screen',
Expand All @@ -87,7 +89,7 @@ def launch_setup(context, *args, **kwargs):
executable='lcd_driver.py',
output='screen',
ros_arguments=['--log-level', 'warn'],
condition=IfCondition(PythonExpression(["'", namespace, "' == 'small'"]))
condition=IfCondition(PythonExpression(["'", namespace, "' == 'big'"]))
)

return [
Expand Down
18 changes: 9 additions & 9 deletions mep3_navigation/params/nav2_params_small.yaml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/small/bt_navigator:
ros__parameters:
use_sim_time: True
use_sim_time: false
global_frame: map
robot_base_frame: base_link
odom_topic: /small/odom
Expand All @@ -22,7 +22,7 @@

/small/controller_server:
ros__parameters:
use_sim_time: True
use_sim_time: false
controller_frequency: 20.0
min_x_velocity_threshold: 0.001
min_y_velocity_threshold: 0.5
Expand Down Expand Up @@ -51,7 +51,7 @@
min_lookahead_dist: 0.15
max_lookahead_dist: 0.5
lookahead_time: 0.625
rotate_to_heading_angular_vel: 15.0
rotate_to_heading_angular_vel: 5.0
transform_tolerance: 0.1
use_velocity_scaled_lookahead_dist: true
min_approach_linear_velocity: 0.05
Expand All @@ -64,9 +64,9 @@
allow_reversing: true
use_rotate_to_heading: false
use_rotate_to_goal: true
kp_angle: 6.0
kp_angle: 4.0
rotate_to_heading_min_angle: 0.785
max_angular_accel: 15.0
max_angular_accel: 5.0
cost_scaling_dist: 0.7
cost_scaling_gain: 1.0
inflation_cost_scaling_factor: 5.0
Expand All @@ -78,7 +78,7 @@
publish_frequency: 5.0
global_frame: odom
robot_base_frame: base_link
use_sim_time: True
use_sim_time: false
rolling_window: True
width: 3
height: 3
Expand Down Expand Up @@ -115,7 +115,7 @@
publish_frequency: 2.0
global_frame: map
robot_base_frame: base_link
use_sim_time: True
use_sim_time: false
rolling_window: True
robot_radius: 0.2
resolution: 0.07
Expand Down Expand Up @@ -162,7 +162,7 @@

/small/planner_server:
ros__parameters:
use_sim_time: True
use_sim_time: false
planner_plugins: ["GridBased"]
expected_planner_frequency: 1.0
GridBased:
Expand All @@ -187,7 +187,7 @@
global_frame: odom
robot_base_frame: base_link
transform_tolerance: 0.1
use_sim_time: true
use_sim_time: false
max_rotational_vel: 1.0
min_rotational_vel: 0.4
rotational_acc_lim: 3.2
Expand Down