Skip to content

Commit 22ac470

Browse files
289 lynx integrate lynx simulation (#351)
* Add lynx startup to repo, only in rviz the link to map not working yet Signed-off-by: Rosalie <rosalie.van.ark@alliander.com> * Adjust controller config location in urdf lynx, but it's the panther version so the lynx version still needs to be added! Signed-off-by: Rosalie <rosalie.van.ark@alliander.com> * Fix linting Signed-off-by: Rosalie <rosalie.van.ark@alliander.com> * Move panther and lynx to new husarion package, as well as the corresponding controller config from rcdt_gazebo Signed-off-by: Rosalie <rosalie.van.ark@alliander.com> * Restore removed config value Signed-off-by: Rosalie <rosalie.van.ark@alliander.com> * Move the nav2 parts from the panther package to its own package Signed-off-by: Rosalie <rosalie.van.ark@alliander.com> * Add ouster lidar and gps configurations, tested via bringup Signed-off-by: Rosalie <rosalie.van.ark@alliander.com> * Fix linting and add Lynx tests Signed-off-by: Rosalie <rosalie.van.ark@alliander.com> * Update documentation Signed-off-by: Rosalie <rosalie.van.ark@alliander.com> * Remove joy_topics.yaml seems it does not seem to be used anymore Signed-off-by: Rosalie <rosalie.van.ark@alliander.com> * Move the gazebo.urdf.xacro files to a common folder since the panther and lynx both use the same Signed-off-by: Rosalie <rosalie.van.ark@alliander.com> * Fix bug in nav2 tests Signed-off-by: Rosalie <rosalie.van.ark@alliander.com> * Add missing license file Signed-off-by: Rosalie <rosalie.van.ark@alliander.com> * Update predefined configurations according to new features from main branch Signed-off-by: Rosalie <rosalie.van.ark@alliander.com> * Fix bug regarding local variable being uninitialized Signed-off-by: Rosalie <rosalie.van.ark@alliander.com> * Update lifecycle node management nav2 Signed-off-by: Rosalie <rosalie.van.ark@alliander.com> * Assign Lifecycle directly to dictionary Signed-off-by: Rosalie <rosalie.van.ark@alliander.com> --------- Signed-off-by: Rosalie <rosalie.van.ark@alliander.com> Signed-off-by: Jelmer de Wolde <jelmer.de.wolde@alliander.com> Signed-off-by: Rosalie van Ark <57712550+rosalievanark@users.noreply.github.com> Co-authored-by: Jelmer de Wolde <jelmer.de.wolde@alliander.com>
1 parent 4690091 commit 22ac470

File tree

72 files changed

+1497
-172
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

72 files changed

+1497
-172
lines changed

docs/content/platforms.md

Lines changed: 14 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ Regarding all vehicles, the general rule we apply for assigning IP addresses fol
4949

5050
### Simulation Panther
5151

52-
A Panther vehicle can be launched in simulation by creating a configuration with an *Vehicle* of type *Panther*. Note that the E-Stop is triggered by default and needs to be released before driving is possible. This can be done by a service call:
52+
A Panther vehicle can be launched in simulation by creating a configuration with a `Vehicle` of type `Panther`. Note that the E-Stop is triggered by default and needs to be released before driving is possible. This can be done by a service call:
5353

5454
```bash
5555
ros2 service call /panther/hardware/e_stop_reset std_srvs/srv/Trigger {}
@@ -82,7 +82,7 @@ The robot can be shut down as follows:
8282
- Wait until all lights are off.
8383
- Disable the battery (switch at the front of the robot)
8484

85-
### Configuration
85+
### Configuration Panther
8686

8787
When the Panther is started, two WiFi networks (*Panther_<serial_number>* and *Panther_5G_<serial_number>*) should be available. One can connect with one of the WiFi networks or connect using a ethernet cable directly to the Teltonika. After connecting, it should be possible to ssh into all three computers.
8888

@@ -100,6 +100,18 @@ We have also cloned the [nmea-gps-docker](https://github.com/husarion/nmea-gps-d
100100
\
101101
The *Lenovo ThinkStation P360* is a powerful computer, used to handle the camera stream. We can run our docker image on this built in computer.
102102

103+
## Lynx
104+
105+
![Lynx](../img/lynx/lynx.png)
106+
107+
### Simulation Lynx
108+
109+
A Lynx vehicle can be launched in simulation by creating a configuration with a `Vehicle` of type `Lynx`.
110+
111+
### Hardware & Configuration Lynx
112+
113+
This section is equivalent to the [Hardware Panther](#hardware-panther) and [Configuration Panther](#configuration-panther) sections, except for the namespace here being `lynx` and the _Lenovo ThinkStation P360_ will be replaced with a different computer.
114+
103115
## Realsense
104116

105117
![Realsense](../img/realsense/realsense.png)

docs/img/lynx/lynx.png

Lines changed: 3 additions & 0 deletions
Loading

docs/img/lynx/lynx.png.license

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
SPDX-FileCopyrightText: Alliander N. V.
2+
3+
SPDX-License-Identifier: Apache-2.0

pyproject.toml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -83,7 +83,7 @@ extra-paths = [
8383
"/home/rcdt/realsense_ws/install/realsense2_camera_msgs/lib/python3.12/site-packages/",
8484
"ros2_ws/install/rcdt_interfaces/lib/python3.12/site-packages/",
8585
"ros2_ws/src/rcdt_franka/",
86-
"ros2_ws/src/rcdt_panther/",
86+
"ros2_ws/src/rcdt_husarion/",
8787
"ros2_ws/src/rcdt_utilities/",
8888
"ros2_ws/src/rcdt_gazebo/",
8989
"ros2_ws/src/rcdt_launch/",

ros2_ws/src/rcdt_gazebo/config/controllers.yaml

Lines changed: 0 additions & 79 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,6 @@
33
# SPDX-License-Identifier: Apache-2.0
44

55
# Based on:
6-
# https://github.com/husarion/husarion_ugv_ros/blob/ros2/husarion_ugv_controller/config/WH01_controller.yaml
76
# https://github.com/frankarobotics/franka_ros2/blob/humble/franka_fr3_moveit_config/config/fr3_ros_controllers.yaml
87

98
/**:
@@ -20,12 +19,6 @@
2019
gripper_action_controller:
2120
type: parallel_gripper_action_controller/GripperActionController
2221

23-
drive_controller:
24-
type: diff_drive_controller/DiffDriveController
25-
26-
imu_broadcaster:
27-
type: imu_sensor_broadcaster/IMUSensorBroadcaster
28-
2922
fr3_arm_controller:
3023
ros__parameters:
3124
allow_nonzero_velocity_at_trajectory_end: true
@@ -52,75 +45,3 @@
5245
max_effort: 0.0
5346
stall_timeout: 1.0
5447
stall_velocity_threshold: 0.001
55-
56-
# IMU specification: https://www.phidgets.com/?tier=3&catid=10&pcid=8&prodid=1025#Tab_Specifications
57-
imu_broadcaster:
58-
ros__parameters:
59-
sensor_name: substitute_me
60-
frame_id: substitute_me
61-
# orientation_stddev: 4.3e-2 rad determined experimentally
62-
static_covariance_orientation:
63-
[1.8e-3, 0.0, 0.0, 0.0, 1.8e-3, 0.0, 0.0, 0.0, 1.8e-3]
64-
# angular_velocity_stdev: 0.59 deg/s (0.01 rad/s) gyroscope white noise sigma, according to the manual
65-
static_covariance_angular_velocity:
66-
[1.0e-4, 0.0, 0.0, 0.0, 1.0e-4, 0.0, 0.0, 0.0, 1.0e-4]
67-
# linear_acceleration_stdev: 2.8 mg (0.0275 m/s^2) accelerometer white noise sigma, according to the manual
68-
static_covariance_linear_acceleration:
69-
[7.6e-4, 0.0, 0.0, 0.0, 7.6e-4, 0.0, 0.0, 0.0, 7.6e-4]
70-
71-
drive_controller:
72-
ros__parameters:
73-
left_wheel_names: [fl_wheel_joint, rl_wheel_joint]
74-
right_wheel_names: [fr_wheel_joint, rr_wheel_joint]
75-
76-
wheel_separation: 0.697
77-
wheel_radius: 0.1825
78-
79-
# For skid drive kinematics it will act as ICR coefficient, kinematic model with ICR
80-
# coefficient isn't totally accurate and this coefficient can differ for various ground types
81-
wheel_separation_multiplier: 1.5
82-
83-
left_wheel_radius_multiplier: 1.0
84-
right_wheel_radius_multiplier: 1.0
85-
86-
publish_rate: 1000.0
87-
odom_frame_id: odom
88-
base_frame_id: base_link
89-
twist_covariance_diagonal: [5.4e-5, 5.4e-5, 0.0, 0.0, 0.0, 1.9e-4] # Values measured experimentally
90-
91-
# Whether to use feedback or commands for odometry calculations
92-
open_loop: false
93-
94-
# Update odometry from velocity
95-
# in sensor fusion only velocity is used and with this setting it is more accurate
96-
position_feedback: false
97-
# velocity computation filtering
98-
velocity_rolling_window_size: 1
99-
100-
enable_odom_tf: true
101-
102-
cmd_vel_timeout: 0.5
103-
#publish_limited_velocity: true
104-
use_stamped_vel: false
105-
106-
# Velocity and acceleration limits
107-
# Whenever a min_* is unspecified, default to -max_*
108-
linear:
109-
x:
110-
has_velocity_limits: true
111-
has_acceleration_limits: true
112-
max_velocity: 2.0 # m/s
113-
# min_velocity - When unspecified `min_velocity=-max_velocity`
114-
max_acceleration: 2.7 # m/s^2
115-
# min_acceleration - When unspecified, `min_acceleration=-max_acceleration`
116-
max_jerk: NAN # m/s^3
117-
118-
angular:
119-
z:
120-
has_velocity_limits: true
121-
has_acceleration_limits: true
122-
max_velocity: 4.0 # rad/s
123-
# min_velocity - When unspecified `min_velocity=-max_velocity`
124-
max_acceleration: 5.74 # rad/s^2
125-
# min_acceleration - When unspecified, `min_acceleration=-max_acceleration`
126-
max_jerk: NAN # rad/s^3
Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
# SPDX-License-Identifier: Apache-2.0
44

55
cmake_minimum_required(VERSION 3.5)
6-
project(rcdt_panther)
6+
project(rcdt_husarion)
77

88
# CMake dependencies:
99
find_package(ament_cmake REQUIRED)
Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -4,9 +4,9 @@ SPDX-FileCopyrightText: Alliander N. V.
44
SPDX-License-Identifier: Apache-2.0
55
-->
66

7-
# RCDT Panther
7+
# RCDT Husarion
88

9-
This repository contains code for use with the Husarion Panther by [Husarion](https://husarion.com).
9+
This repository contains code for use with the Husarion Panther & Lynx by [Husarion](https://husarion.com).
1010
It is intended to be used alongside the other repositories in [RCDT robotics](https://github.com/alliander-opensource/rcdt_robotics).
1111

1212
## License
Lines changed: 91 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,91 @@
1+
# SPDX-FileCopyrightText: Alliander N. V.
2+
#
3+
# SPDX-License-Identifier: Apache-2.0
4+
5+
# Based on:
6+
# https://github.com/husarion/husarion_ugv_ros/blob/2.3.1/husarion_ugv_controller/config/WH05_controller.yaml
7+
8+
/**:
9+
controller_manager:
10+
ros__parameters:
11+
update_rate: 1000
12+
13+
joint_state_broadcaster:
14+
type: joint_state_broadcaster/JointStateBroadcaster
15+
16+
drive_controller:
17+
type: diff_drive_controller/DiffDriveController
18+
19+
imu_broadcaster:
20+
type: imu_sensor_broadcaster/IMUSensorBroadcaster
21+
22+
# IMU specification: https://www.phidgets.com/?tier=3&catid=10&pcid=8&prodid=1025#Tab_Specifications
23+
imu_broadcaster:
24+
ros__parameters:
25+
sensor_name: <namespace>/imu
26+
frame_id: <namespace>/imu_link
27+
# orientation_stddev: 4.3e-2 rad determined experimentally
28+
static_covariance_orientation: [1.8e-3, 0.0, 0.0, 0.0, 1.8e-3, 0.0, 0.0, 0.0, 1.8e-3]
29+
# angular_velocity_stdev: 0.59 deg/s (0.01 rad/s) gyroscope white noise sigma, according to the manual
30+
static_covariance_angular_velocity: [1.0e-4, 0.0, 0.0, 0.0, 1.0e-4, 0.0, 0.0, 0.0, 1.0e-4]
31+
# linear_acceleration_stdev: 2.8 mg (0.0275 m/s^2) accelerometer white noise sigma, according to the manual
32+
static_covariance_linear_acceleration: [7.6e-4, 0.0, 0.0, 0.0, 7.6e-4, 0.0, 0.0, 0.0, 7.6e-4]
33+
34+
drive_controller:
35+
ros__parameters:
36+
left_wheel_names: [fl_wheel_joint, rl_wheel_joint]
37+
right_wheel_names: [fr_wheel_joint, rr_wheel_joint]
38+
39+
wheel_separation: 0.45
40+
wheel_radius: 0.144
41+
42+
# For skid drive kinematics it will act as ICR coefficient, kinematic model with ICR
43+
# coefficient isn't totally accurate and this coefficient can differ for various ground types
44+
wheel_separation_multiplier: 1.6
45+
46+
# This parameter depends on wheels pressure and robot mass.
47+
# It was measured experimentally without load and with the pressure of 1.2 bar.
48+
left_wheel_radius_multiplier: 0.964
49+
right_wheel_radius_multiplier: 0.964
50+
51+
publish_rate: 100.0
52+
odom_frame_id: odom
53+
base_frame_id: base_link
54+
twist_covariance_diagonal: [5.4e-5, 5.4e-5, 0.0, 0.0, 0.0, 1.9e-4] # Values measured experimentally
55+
56+
# Whether to use feedback or commands for odometry calculations
57+
open_loop: false
58+
59+
# Update odometry from velocity
60+
# in sensor fusion only velocity is used and with this setting it is more accurate
61+
position_feedback: false
62+
# velocity computation filtering
63+
velocity_rolling_window_size: 1
64+
65+
enable_odom_tf: true
66+
67+
cmd_vel_timeout: 0.2
68+
publish_limited_velocity: false
69+
70+
# Velocity and acceleration limits
71+
linear:
72+
x:
73+
max_velocity: 1.5 # m/s
74+
min_velocity: -1.5 # m/s
75+
max_acceleration: 2.1 # m/s^2
76+
max_deceleration: -2.1 # m/s^2
77+
max_acceleration_reverse: -2.1 # m/s^2
78+
max_deceleration_reverse: 2.1 # m/s^2
79+
max_jerk: .NAN # m/s^3
80+
min_jerk: .NAN # m/s^3
81+
82+
angular:
83+
z:
84+
max_velocity: 4.0 # rad/s
85+
min_velocity: -4.0 # rad/s
86+
max_acceleration: 5.74 # rad/s^2
87+
max_deceleration: -5.74 # rad/s^2
88+
max_acceleration_reverse: -5.74 # rad/s^2
89+
max_deceleration_reverse: 5.74 # rad/s^2
90+
max_jerk: .NAN # rad/s^3
91+
min_jerk: .NAN # rad/s^3
Lines changed: 92 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,92 @@
1+
# SPDX-FileCopyrightText: Alliander N. V.
2+
#
3+
# SPDX-License-Identifier: Apache-2.0
4+
5+
# Based on:
6+
# https://github.com/husarion/husarion_ugv_ros/blob/2.3.1/husarion_ugv_controller/config/WH01_controller.yaml
7+
8+
/**:
9+
controller_manager:
10+
ros__parameters:
11+
update_rate: 1000
12+
13+
joint_state_broadcaster:
14+
type: joint_state_broadcaster/JointStateBroadcaster
15+
16+
drive_controller:
17+
type: diff_drive_controller/DiffDriveController
18+
19+
imu_broadcaster:
20+
type: imu_sensor_broadcaster/IMUSensorBroadcaster
21+
22+
# IMU specification: https://www.phidgets.com/?tier=3&catid=10&pcid=8&prodid=1025#Tab_Specifications
23+
imu_broadcaster:
24+
ros__parameters:
25+
sensor_name: substitute_me
26+
frame_id: substitute_me
27+
# orientation_stddev: 4.3e-2 rad determined experimentally
28+
static_covariance_orientation:
29+
[1.8e-3, 0.0, 0.0, 0.0, 1.8e-3, 0.0, 0.0, 0.0, 1.8e-3]
30+
# angular_velocity_stdev: 0.59 deg/s (0.01 rad/s) gyroscope white noise sigma, according to the manual
31+
static_covariance_angular_velocity:
32+
[1.0e-4, 0.0, 0.0, 0.0, 1.0e-4, 0.0, 0.0, 0.0, 1.0e-4]
33+
# linear_acceleration_stdev: 2.8 mg (0.0275 m/s^2) accelerometer white noise sigma, according to the manual
34+
static_covariance_linear_acceleration:
35+
[7.6e-4, 0.0, 0.0, 0.0, 7.6e-4, 0.0, 0.0, 0.0, 7.6e-4]
36+
37+
drive_controller:
38+
ros__parameters:
39+
left_wheel_names: [fl_wheel_joint, rl_wheel_joint]
40+
right_wheel_names: [fr_wheel_joint, rr_wheel_joint]
41+
42+
wheel_separation: 0.697
43+
wheel_radius: 0.1825
44+
45+
# For skid drive kinematics it will act as ICR coefficient, kinematic model with ICR
46+
# coefficient isn't totally accurate and this coefficient can differ for various ground types
47+
wheel_separation_multiplier: 1.5
48+
49+
left_wheel_radius_multiplier: 1.0
50+
right_wheel_radius_multiplier: 1.0
51+
52+
publish_rate: 1000.0
53+
odom_frame_id: odom
54+
base_frame_id: base_link
55+
twist_covariance_diagonal: [5.4e-5, 5.4e-5, 0.0, 0.0, 0.0, 1.9e-4] # Values measured experimentally
56+
57+
# Whether to use feedback or commands for odometry calculations
58+
open_loop: false
59+
60+
# Update odometry from velocity
61+
# in sensor fusion only velocity is used and with this setting it is more accurate
62+
position_feedback: false
63+
# velocity computation filtering
64+
velocity_rolling_window_size: 1
65+
66+
enable_odom_tf: true
67+
68+
cmd_vel_timeout: 0.5
69+
#publish_limited_velocity: true
70+
use_stamped_vel: false
71+
72+
# Velocity and acceleration limits
73+
# Whenever a min_* is unspecified, default to -max_*
74+
linear:
75+
x:
76+
has_velocity_limits: true
77+
has_acceleration_limits: true
78+
max_velocity: 2.0 # m/s
79+
# min_velocity - When unspecified `min_velocity=-max_velocity`
80+
max_acceleration: 2.7 # m/s^2
81+
# min_acceleration - When unspecified, `min_acceleration=-max_acceleration`
82+
max_jerk: NAN # m/s^3
83+
84+
angular:
85+
z:
86+
has_velocity_limits: true
87+
has_acceleration_limits: true
88+
max_velocity: 4.0 # rad/s
89+
# min_velocity - When unspecified `min_velocity=-max_velocity`
90+
max_acceleration: 5.74 # rad/s^2
91+
# min_acceleration - When unspecified, `min_acceleration=-max_acceleration`
92+
max_jerk: NAN # rad/s^3
File renamed without changes.

0 commit comments

Comments
 (0)