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

Rename stderr params #166

Merged
merged 1 commit into from
Aug 4, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions panther_description/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,10 @@ Parameter `wheel_config_path` allows using non-standard wheels with Panther robo
- `mesh_package` - ROS package name to search for custom meshes. Used in evaluation **$(find my_amazing_package)/**.
- `folder_path` - path used to search for mesh files within the ROS package.
- `kinematics` - kinematics type. Possible options: `differential`, `mecanum`.
- `odom_stderr` - standard deviation used to populated odometry message:
- `vel_x` - standard deviation for linear velocity in **x** direction.
- `vel_y` - standard deviation for linear velocity in **y** direction.
- `vel_yaw` - standard deviation for angular velocity alongside **z** axis.
KmakD marked this conversation as resolved.
Show resolved Hide resolved

Wheels have to be named as follows:
- `wheel_collision.stl` - wheel collision mesh.
Expand Down
6 changes: 2 additions & 4 deletions panther_description/config/WH01.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,5 @@ mesh_package: panther_description
folder_path: meshes/WH01
kinematics: differential

# Value measured (using Husarion research toolkit)
velocity_x_stderr: 3.2e-3
velocity_y_stderr: 1.4e-3
velocity_yaw_stderr: 8.5e-3
# Values measured experimentally
odom_stderr: { vel_x: 3.2e-3, vel_y: 1.4e-3, vel_yaw: 8.5e-3 }
4 changes: 1 addition & 3 deletions panther_description/config/WH02.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,4 @@ folder_path: meshes/WH02
kinematics: mecanum

# Selected intuitively based on WH01 results
velocity_x_stderr: 3.2e-3
velocity_y_stderr: 3.2e-3
velocity_yaw_stderr: 8.5e-3
odom_stderr: { vel_x: 3.2e-3, vel_y: 3.2e-3, vel_yaw: 8.5e-3 }
4 changes: 1 addition & 3 deletions panther_description/config/WH04.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,4 @@ folder_path: meshes/WH04
kinematics: differential

# Selected intuitively based on WH01 results
velocity_x_stderr: 1.6e-3
velocity_y_stderr: 7.3e-4
velocity_yaw_stderr: 4.3e-3
odom_stderr: { vel_x: 1.6e-3, vel_y: 7.3e-4, vel_yaw: 4.3e-3 }
3 changes: 3 additions & 0 deletions panther_driver/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,9 @@ For a `/joint_states` message is carrying given data:
- `~kinematics` [*string*, default: **differential**]: kinematics type, possible are: differential, mecanum.
- `~motor_torque_constant` [*float*, default: **2.6149**]: constant used to estimate torque.
- `~odom_frame` [*string*, default: **odom**]: the name of the odom frame.
- `~odom_stderr/vel_x` [*float*, default: **3.2e-3**]: standard error used to place in covariance matrix, after squaring, in odometry message.
- `~odom_stderr/vel_y` [*float*, default: **3.2e-3**]: standard error used to place in covariance matrix, after squaring, in odometry message.
- `~odom_stderr/vel_yaw` [*float*, default: **8.5e-3**]: standard error used to place in covariance matrix, after squaring, in odometry message.
- `~publish_joints` [*bool*, default: **true**]: whether to publish robot joints states.
- `~publish_odometry` [*bool*, default: **true**]: whether to publish robot odometry.
- `~publish_pose` [*bool*, default: **true**]: whether to publish robot pose.
Expand Down
6 changes: 3 additions & 3 deletions panther_driver/src/driver_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -76,9 +76,9 @@ def __init__(self, name: str) -> None:
self._motor_torque_constant = rospy.get_param('~motor_torque_constant', 2.6149)
self._gear_ratio = rospy.get_param('~gear_ratio', 30.08)
self._encoder_resolution = rospy.get_param('~encoder_resolution', 400 * 4)
self._v_x_var = float(rospy.get_param('~velocity_x_stderr', 3.2e-3))**2
self._v_y_var = float(rospy.get_param('~velocity_y_stderr', 3.2e-3))**2
self._v_yaw_var = float(rospy.get_param('~velocity_yaw_stderr', 8.5e-3))**2
self._v_x_var = float(rospy.get_param('~odom_stderr/vel_x', 3.2e-3))**2
self._v_y_var = float(rospy.get_param('~odom_stderr/vel_y', 3.2e-3))**2
self._v_yaw_var = float(rospy.get_param('~odom_stderr/vel_yaw', 8.5e-3))**2

self._publish_tf = rospy.get_param('~publish_tf', True)
self._publish_odom = rospy.get_param('~publish_odometry', True)
Expand Down
Loading