diff --git a/devel/core_algorithm/fusion/CMakeLists.txt b/devel/core_algorithm/fusion/CMakeLists.txt
index 8929f86..d459ae6 100644
--- a/devel/core_algorithm/fusion/CMakeLists.txt
+++ b/devel/core_algorithm/fusion/CMakeLists.txt
@@ -52,8 +52,9 @@ install(TARGETS
DESTINATION lib/${PROJECT_NAME}
)
-install(
- DIRECTORY launch
+install(DIRECTORY
+ launch
+ param
DESTINATION share/${PROJECT_NAME}
)
diff --git a/devel/core_algorithm/fusion/include/fusion/ekf.hpp b/devel/core_algorithm/fusion/include/fusion/ekf.hpp
index efed7b2..7505bf0 100644
--- a/devel/core_algorithm/fusion/include/fusion/ekf.hpp
+++ b/devel/core_algorithm/fusion/include/fusion/ekf.hpp
@@ -17,7 +17,7 @@ class EKF{
void Xprediction(Eigen::Vector3d, Eigen::Matrix3d);
void Vprediction(Eigen::Vector3d, Eigen::Matrix3d, double);
- void correction(Eigen::Vector3d, Eigen::Matrix3d);
+ void correction(Eigen::Vector3d, Eigen::Matrix3d, Eigen::Matrix3d);
Eigen::Vector3d getPose();
Eigen::Matrix3d getCov();
diff --git a/devel/core_algorithm/fusion/include/fusion/fusion_node.hpp b/devel/core_algorithm/fusion/include/fusion/fusion_node.hpp
index 360f530..1d36c71 100644
--- a/devel/core_algorithm/fusion/include/fusion/fusion_node.hpp
+++ b/devel/core_algorithm/fusion/include/fusion/fusion_node.hpp
@@ -52,14 +52,21 @@ class FusionNode : public rclcpp::Node{
Eigen::Matrix3d local_cov;
Eigen::Matrix3d cbcam_cov;
Eigen::Matrix3d obcam_cov;
- Eigen::Matrix3d init_rot;
+ Eigen::Matrix3d global_h;
+ Eigen::Matrix3d cbcam_h;
+ Eigen::Matrix3d obcam_h;
bool if_align;
+ bool spin_control;
int pose_modes[4];
+ double spin_threshold;
+
double max_dt_align;
double min_dt_align;
+
+ double lidar_yaw;
double prev_pred_time;
diff --git a/devel/core_algorithm/fusion/launch/b_running_launch.py b/devel/core_algorithm/fusion/launch/b_running_launch.py
deleted file mode 100644
index 683620b..0000000
--- a/devel/core_algorithm/fusion/launch/b_running_launch.py
+++ /dev/null
@@ -1,191 +0,0 @@
-#!/usr/bin/env python3
-from launch import LaunchDescription
-from launch.actions import DeclareLaunchArgument, GroupAction, IncludeLaunchDescription, SetLaunchConfiguration, TimerAction
-from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
-from launch.launch_description_sources import PythonLaunchDescriptionSource, AnyLaunchDescriptionSource
-from launch_ros.actions import Node
-from launch_ros.substitutions import FindPackageShare
-
-
-def generate_launch_description():
- rival_name = LaunchConfiguration('rival_name')
- side = LaunchConfiguration('side')
-
- local_filter_launch_path = PathJoinSubstitution([
- FindPackageShare('wheel_inertial_odometry'),
- 'launch',
- 'local.launch.py'
- ])
-
- # rplidar_launch = PathJoinSubstitution([
- # FindPackageShare('lidar_localization_pkg'),
- # 'launch',
- # 'firmware',
- # 'rplidar_s3_launch.py'
- # ])
- ydlidar_launch = PathJoinSubstitution([
- FindPackageShare('lidar_localization'),
- 'launch',
- 'firmware',
- 'ydlidar_launch.py'
- ])
-
- obstacle_extractor_launch = PathJoinSubstitution([
- FindPackageShare('lidar_localization'),
- 'launch',
- 'obstacle_extractor_launch.xml'
- ])
-
-# healthcheck_node = Node(
-# package='healthcheck',
-# executable='healthcheck_node',
-# name='healthcheck_node',
-# output='screen'
- # ,remappings=[
- # ['/vision/aruco/robot/single/average_pose', '/vision/aruco/robot_pose']
- # ]
-# )
-
- ekf_node = Node(
- package='fusion',
- executable='ekf_node.py',
- name='ekf',
- output='screen',
- parameters=[{
- 'use_cam': 0,
- 'robot_parent_frame_id': 'map',
- 'robot_frame_id': 'base_footprint',
- '/use_sim_time': False,
- 'q_linear': 1.2e-6,
- 'q_angular': 1.7e-7,
- 'r_camra_linear': 1e-2,
- 'r_camra_angular': 0.1,
- 'r_threshold_xy': 1e-2,
- 'r_threshold_theta': 1e-1
- }],
- )
-
- lidar_node = Node(
- package='lidar_localization',
- executable='lidar_member_function.py',
- name='lidar_localization_node',
- arguments=['--ros-args', '--log-level', 'info'],
- output='screen',
- parameters=[{
- 'side': side,
- 'debug_mode': False,
- 'visualize_candidate': True,
- 'likelihood_threshold': 0.8,
- 'consistency_threshold': 0.95,
- 'lidar_multiplier': 0.987
- }]
- )
-
- local_filter_launch = IncludeLaunchDescription(
- AnyLaunchDescriptionSource(local_filter_launch_path)
- )
-
- rival_node = Node(
- package='rival_localization',
- executable='rival_localization',
- name='rival_localization',
- output='screen',
- parameters=[
- {
- 'robot_name': 'robot',
- 'frequency': 10.0,
- 'x_max': 3.0,
- 'x_min': 0.0,
- 'y_max': 2.0,
- 'y_min': 0.0,
- 'vel_lpf_gain': 0.9,
- 'locking_rad': 0.3,
- 'lockrad_growing_rate': 0.3,
- 'is_me': 0.3,
- 'cam_weight': 6.0,
- 'obs_weight': 10.0,
- 'side_weight': 2.0,
- 'cam_side_threshold': 0.2,
- 'side_obs_threshold': 0.2,
- 'obs_cam_threshold': 0.2,
- 'crossed_areas': [
- 2.55, 3.0, 0.65, 1.1,
- 2.4, 2.85, 1.55, 2.0,
- 2.0, 3.0, 0.0, 0.15,
- 1.0, 2.0, 0.0, 0.4,
- 0.0, 1.0, 0.0, 0.15,
- 0.0, 0.45, 0.65, 1.1,
- 0.15, 0.6, 1.55, 2.0,
- 1.05, 1.95, 1.50, 2.0
- ]
- }
- ],
- remappings=[
- ('raw_pose', PathJoinSubstitution([rival_name, '/raw_pose'])),
- ('/ceiling_rival/pose','/vision/aruco/rival_pose')
- ]
- )
-
- rival_obstacle_node = Node(
- package='obstacle_detector',
- executable='obstacle_extractor_node',
- name='obstacle_detector_to_robot',
- parameters=[{
- 'frame_id': 'map',
- 'active': True,
- 'use_scan': True,
- 'use_pcl': False,
- 'use_split_and_merge': True,
- 'circles_from_visibles': True,
- 'discard_converted_segments': False,
- 'transform_coordinates': True,
- 'min_group_points': 5,
- 'max_group_distance': 0.04,
- 'distance_proportion': 0.00628,
- 'max_split_distance': 0.02,
- 'max_merge_separation': 0.25,
- 'max_merge_spread': 0.02,
- 'max_circle_radius': 0.2,
- 'radius_enlargement': 0.05,
- 'pose_array': True
- }],
- remappings=[
- ('raw_obstacles', '/obstacles_to_map'),
- ('scan', '/scan'),
- ('raw_obstacles_visualization_pcl', 'raw_obstacle_visualization_to_map_pcl')
- ]
- )
-
- static_tf = Node(
- package='tf2_ros',
- executable='static_transform_publisher',
- name='robot_to_laser',
- output='screen',
- arguments=[
- '--x', '0', '--y', '0', '--z', '0',
- '--roll', '0', '--pitch', '0', '--yaw', '-1.633628',
- '--frame-id', 'base_footprint',
- '--child-frame-id', 'laser'
- ]
- )
-
- # rplidar_include = IncludeLaunchDescription(PythonLaunchDescriptionSource(rplidar_launch))
- ydlidar_include = IncludeLaunchDescription(PythonLaunchDescriptionSource(ydlidar_launch))
- obstacle_extractor_include = IncludeLaunchDescription(AnyLaunchDescriptionSource(obstacle_extractor_launch))
-
- return LaunchDescription([
- DeclareLaunchArgument('rival_name', default_value='rival'),
- DeclareLaunchArgument('side', default_value='1'),
-
- static_tf,
- ydlidar_include,
- obstacle_extractor_include,
-
- ekf_node,
-# healthcheck_node,
-
- # TimerAction(period=2.0, actions=[ekf_node]),
- TimerAction(period=4.0, actions=[lidar_node]),
- TimerAction(period=6.0, actions=[local_filter_launch]),
- TimerAction(period=8.0, actions=[rival_node, rival_obstacle_node])
- ])
\ No newline at end of file
diff --git a/devel/core_algorithm/fusion/launch/bag_test.launch b/devel/core_algorithm/fusion/launch/bag_test.launch
deleted file mode 100644
index 617a0dc..0000000
--- a/devel/core_algorithm/fusion/launch/bag_test.launch
+++ /dev/null
@@ -1,47 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
\ No newline at end of file
diff --git a/devel/core_algorithm/fusion/launch/blue.launch b/devel/core_algorithm/fusion/launch/blue.launch
deleted file mode 100644
index 07f8334..0000000
--- a/devel/core_algorithm/fusion/launch/blue.launch
+++ /dev/null
@@ -1,58 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
\ No newline at end of file
diff --git a/devel/core_algorithm/fusion/launch/fake_cam.launch b/devel/core_algorithm/fusion/launch/fake_cam.launch
deleted file mode 100644
index fd04253..0000000
--- a/devel/core_algorithm/fusion/launch/fake_cam.launch
+++ /dev/null
@@ -1,20 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
\ No newline at end of file
diff --git a/devel/core_algorithm/fusion/launch/fusion.launch.xml b/devel/core_algorithm/fusion/launch/fusion.launch.xml
index 2a9f491..f1e2ca7 100644
--- a/devel/core_algorithm/fusion/launch/fusion.launch.xml
+++ b/devel/core_algorithm/fusion/launch/fusion.launch.xml
@@ -5,7 +5,7 @@
-
+
diff --git a/devel/core_algorithm/fusion/launch/run.launch b/devel/core_algorithm/fusion/launch/run.launch
deleted file mode 100644
index f40af4d..0000000
--- a/devel/core_algorithm/fusion/launch/run.launch
+++ /dev/null
@@ -1,38 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
\ No newline at end of file
diff --git a/devel/core_algorithm/fusion/launch/y_running_launch.py b/devel/core_algorithm/fusion/launch/y_running_launch.py
deleted file mode 100644
index b298b1b..0000000
--- a/devel/core_algorithm/fusion/launch/y_running_launch.py
+++ /dev/null
@@ -1,192 +0,0 @@
-#!/usr/bin/env python3
-from launch import LaunchDescription
-from launch.actions import DeclareLaunchArgument, GroupAction, IncludeLaunchDescription, SetLaunchConfiguration, TimerAction
-from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
-from launch.launch_description_sources import PythonLaunchDescriptionSource, AnyLaunchDescriptionSource
-from launch_ros.actions import Node
-from launch_ros.substitutions import FindPackageShare
-
-
-def generate_launch_description():
- rival_name = LaunchConfiguration('rival_name')
- side = LaunchConfiguration('side')
-
- fusion_launch_path = PathJoinSubstitution([
- FindPackageShare('fusion'),
- 'launch',
- 'fusion.launch.xml'
- ])
-
- local_filter_launch_path = PathJoinSubstitution([
- FindPackageShare('wheel_inertial_odometry'),
- 'launch',
- 'local.launch.py'
- ])
-
- # rplidar_launch = PathJoinSubstitution([
- # FindPackageShare('lidar_localization_pkg'),
- # 'launch',
- # 'firmware',
- # 'rplidar_s3_launch.py'
- # ])
- ydlidar_launch = PathJoinSubstitution([
- FindPackageShare('lidar_localization'),
- 'launch',
- 'firmware',
- 'ydlidar_launch.py'
- ])
-
- obstacle_extractor_launch = PathJoinSubstitution([
- FindPackageShare('lidar_localization'),
- 'launch',
- 'obstacle_extractor_launch.xml'
- ])
-
-# healthcheck_node = Node(
-# package='healthcheck',
-# executable='healthcheck_node',
-# name='healthcheck_node',
-# output='screen'
-# # ,remappings=[
-# # ['/vision/aruco/robot/single/average_pose', '/vision/aruco/robot_pose']
-# # ]
-# )
-
- init_pose = Node(
- package='fusion',
- executable='pub_init',
- name='pub_init',
- output='screen',
- parameters=[
- '/home/user/localization-ws/src/core_algorithm/fusion/param/fusion.yaml'
- ]
- )
-
- lidar_node = Node(
- package='lidar_localization',
- executable='lidar_member_function.py',
- name='lidar_localization_node',
- arguments=['--ros-args', '--log-level', 'info'],
- output='screen',
- parameters=[{
- 'side': side,
- 'debug_mode': False,
- 'visualize_candidate': True,
- 'likelihood_threshold': 0.8,
- 'consistency_threshold': 0.95,
- 'lidar_multiplier': 0.987
- }]
- )
-
- fusion_launch = IncludeLaunchDescription(
- AnyLaunchDescriptionSource(fusion_launch_path)
- )
-
- local_filter_launch = IncludeLaunchDescription(
- AnyLaunchDescriptionSource(local_filter_launch_path)
- )
-
- rival_node = Node(
- package='rival_localization',
- executable='rival_localization',
- name='rival_localization',
- output='screen',
- parameters=[
- {
- 'robot_name': 'robot',
- 'frequency': 10.0,
- 'x_max': 3.0,
- 'x_min': 0.0,
- 'y_max': 2.0,
- 'y_min': 0.0,
- 'vel_lpf_gain': 0.9,
- 'locking_rad': 0.3,
- 'lockrad_growing_rate': 0.3,
- 'is_me': 0.3,
- 'cam_weight': 6.0,
- 'obs_weight': 10.0,
- 'side_weight': 2.0,
- 'cam_side_threshold': 0.2,
- 'side_obs_threshold': 0.2,
- 'obs_cam_threshold': 0.2,
- 'crossed_areas': [
- 2.55, 3.0, 0.65, 1.1,
- 2.4, 2.85, 1.55, 2.0,
- 2.0, 3.0, 0.0, 0.15,
- 1.0, 2.0, 0.0, 0.4,
- 0.0, 1.0, 0.0, 0.15,
- 0.0, 0.45, 0.65, 1.1,
- 0.15, 0.6, 1.55, 2.0,
- 1.05, 1.95, 1.50, 2.0
- ]
- }
- ],
- remappings=[
- ('raw_pose', PathJoinSubstitution([rival_name, '/raw_pose'])),
- ('/ceiling_rival/pose','/vision/aruco/rival_pose')
- ]
- )
-
- rival_obstacle_node = Node(
- package='obstacle_detector',
- executable='obstacle_extractor_node',
- name='obstacle_detector_to_robot',
- parameters=[{
- 'frame_id': 'map',
- 'active': True,
- 'use_scan': True,
- 'use_pcl': False,
- 'use_split_and_merge': True,
- 'circles_from_visibles': True,
- 'discard_converted_segments': False,
- 'transform_coordinates': True,
- 'min_group_points': 5,
- 'max_group_distance': 0.04,
- 'distance_proportion': 0.00628,
- 'max_split_distance': 0.02,
- 'max_merge_separation': 0.25,
- 'max_merge_spread': 0.02,
- 'max_circle_radius': 0.2,
- 'radius_enlargement': 0.05,
- 'pose_array': True
- }],
- remappings=[
- ('raw_obstacles', '/obstacles_to_map'),
- ('scan', '/scan'),
- ('raw_obstacles_visualization_pcl', 'raw_obstacle_visualization_to_map_pcl')
- ]
- )
-
- static_tf = Node(
- package='tf2_ros',
- executable='static_transform_publisher',
- name='robot_to_laser',
- output='screen',
- arguments=[
- '--x', '0', '--y', '0', '--z', '0',
- '--roll', '0', '--pitch', '0', '--yaw', '-1.633628',
- '--frame-id', 'base_footprint',
- '--child-frame-id', 'laser'
- ]
- )
-
- # rplidar_include = IncludeLaunchDescription(PythonLaunchDescriptionSource(rplidar_launch))
- ydlidar_include = IncludeLaunchDescription(PythonLaunchDescriptionSource(ydlidar_launch))
- obstacle_extractor_include = IncludeLaunchDescription(AnyLaunchDescriptionSource(obstacle_extractor_launch))
-
- return LaunchDescription([
- DeclareLaunchArgument('rival_name', default_value='rival'),
- DeclareLaunchArgument('side', default_value='0'),
-
- static_tf,
- ydlidar_include,
- obstacle_extractor_include,
-
-# healthcheck_node,
-
- TimerAction(period=0.5, actions=[init_pose]),
- TimerAction(period=1.0, actions=[fusion_launch]),
- TimerAction(period=1.5, actions=[lidar_node]),
- TimerAction(period=2.0, actions=[local_filter_launch]),
- TimerAction(period=2.5, actions=[rival_node, rival_obstacle_node])
- ])
\ No newline at end of file
diff --git a/devel/core_algorithm/fusion/launch/yellow.launch b/devel/core_algorithm/fusion/launch/yellow.launch
deleted file mode 100644
index 9c7f222..0000000
--- a/devel/core_algorithm/fusion/launch/yellow.launch
+++ /dev/null
@@ -1,56 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
\ No newline at end of file
diff --git a/devel/core_algorithm/fusion/param/fusion.yaml b/devel/core_algorithm/fusion/param/fusion.yaml
index 069c0cb..58d5aa1 100644
--- a/devel/core_algorithm/fusion/param/fusion.yaml
+++ b/devel/core_algorithm/fusion/param/fusion.yaml
@@ -1,14 +1,17 @@
fusion_node:
ros__parameters:
- align_timestamp: false
+ align_timestamp: true
+ spin_control: false
+
+ spin_threshold: 1.2
max_dt_align: 0.3
min_dt_align: 0.05
- cb_cov_x: 4e-4
- cb_cov_y: 4e-4
- cb_cov_yaw: 4e-4
+ cb_cov_x: 6.4e-3
+ cb_cov_y: 6.4e-3
+ cb_cov_yaw: 0.2739
- ob_cov_x: 4e-4
- ob_cov_y: 4e-4
- ob_cov_yaw: 4e-4
\ No newline at end of file
+ ob_cov_x: 6.4e-3
+ ob_cov_y: 6.4e-3
+ ob_cov_yaw: 0.2739
\ No newline at end of file
diff --git a/devel/core_algorithm/fusion/src/ekf.cpp b/devel/core_algorithm/fusion/src/ekf.cpp
index fa9948a..fd15df2 100644
--- a/devel/core_algorithm/fusion/src/ekf.cpp
+++ b/devel/core_algorithm/fusion/src/ekf.cpp
@@ -21,7 +21,7 @@ void EKF::Xprediction(Eigen::Vector3d x, Eigen::Matrix3d R){
if(this->robot_state.mu(2) > M_PI || this->robot_state.mu(2) < -M_PI)
this->robot_state.mu(2) = angleNormalizing(this->robot_state.mu(2));
- this->robot_state.sigma = R;
+ this->robot_state.sigma += R;
}
void EKF::Vprediction(Eigen::Vector3d u, Eigen::Matrix3d R, double dt){
@@ -31,26 +31,35 @@ void EKF::Vprediction(Eigen::Vector3d u, Eigen::Matrix3d R, double dt){
double sin_dt = sin(u(2)*dt);
Eigen::Matrix3d d_state;
- d_state << (sin_theta*(cos_dt-1)+cos_theta*sin_dt)/u(2), (cos_theta*(cos_dt-1)-sin_theta*sin_dt)/u(2), 0,
- -(cos_theta*(cos_dt-1)-sin_theta*sin_dt)/u(2), (sin_theta*(cos_dt-1)+cos_theta*sin_dt)/u(2), 0,
- 0, 0, dt;
-
+ if(abs(u(2))>0.001){
+ d_state << (sin_theta*(cos_dt-1)+cos_theta*sin_dt)/u(2), (cos_theta*(cos_dt-1)-sin_theta*sin_dt)/u(2), 0,
+ -(cos_theta*(cos_dt-1)-sin_theta*sin_dt)/u(2), (sin_theta*(cos_dt-1)+cos_theta*sin_dt)/u(2), 0,
+ 0, 0, dt;
+ }
+ else {
+ d_state << cos(this->robot_state.mu(2))*dt, -sin(this->robot_state.mu(2))*dt, 0,
+ sin(this->robot_state.mu(2))*dt, cos(this->robot_state.mu(2))*dt, 0,
+ 0, 0, 1;
+ }
this->robot_state.mu += d_state*u;
if(this->robot_state.mu(2) > M_PI || this->robot_state.mu(2) < -M_PI)
this->robot_state.mu(2) = angleNormalizing(this->robot_state.mu(2));
- this->robot_state.sigma = R;
+ this->robot_state.sigma += R;
}
-void EKF::correction(Eigen::Vector3d z, Eigen::Matrix3d Q){
+void EKF::correction(Eigen::Vector3d z, Eigen::Matrix3d H, Eigen::Matrix3d Q){
Eigen::Matrix3d K;
- K = this->robot_state.sigma*(this->robot_state.sigma+Q).inverse();
+ K = this->robot_state.sigma*H.transpose()*(H*this->robot_state.sigma*H.transpose()+Q).inverse();
this->robot_state.mu += K*(z-this->robot_state.mu);
+ if(this->robot_state.mu(2) > M_PI || this->robot_state.mu(2) < -M_PI)
+ this->robot_state.mu(2) = angleNormalizing(this->robot_state.mu(2));
+
Eigen::Matrix3d I = Eigen::Matrix3d::Identity();
- this->robot_state.sigma = (I-K)*this->robot_state.sigma;
+ this->robot_state.sigma = (I-K*H)*this->robot_state.sigma;
}
Eigen::Vector3d EKF::getPose(){
diff --git a/devel/core_algorithm/fusion/src/fusion_node.cpp b/devel/core_algorithm/fusion/src/fusion_node.cpp
index 9764ede..5be1df0 100644
--- a/devel/core_algorithm/fusion/src/fusion_node.cpp
+++ b/devel/core_algorithm/fusion/src/fusion_node.cpp
@@ -7,6 +7,8 @@
#include "utils/gen_functs.hpp"
#include "utils/enumerators.hpp"
+#include
+
FusionNode::FusionNode() : Node("fusion_node"){
this->tf_static_broadcaster = std::make_unique(*this);
this->tf_buffer = std::make_unique(this->get_clock());
@@ -17,12 +19,21 @@ FusionNode::FusionNode() : Node("fusion_node"){
this->local_cov.setIdentity();
this->cbcam_cov.setIdentity();
this->obcam_cov.setIdentity();
- this->init_rot.setIdentity();
+ this->global_h.setIdentity();
+ this->cbcam_h.setIdentity();
+ this->obcam_h.setIdentity();
+
+ this->lidar_yaw = 0.0;
for(int i=0; i<4; i++){
this->pose_modes[i] = static_cast(ModeEnum::ACTIVE);
}
+
+ this->cbcam_h(2, 2) = 0.0;
+ this->obcam_h(2, 2) = 0.0;
+
+
rclcpp::QoS qos(1);
qos.reliability(RMW_QOS_POLICY_RELIABILITY_RELIABLE);
qos.durability(RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL);
@@ -40,6 +51,12 @@ FusionNode::FusionNode() : Node("fusion_node"){
this->declare_parameter("align_timestamp", false);
this->if_align = this->get_parameter("align_timestamp").as_bool();
+ this->declare_parameter("spin_control", false);
+ this->spin_control = this->get_parameter("spin_control").as_bool();
+
+ this->declare_parameter("spin_threshold", 1.2);
+ this->spin_threshold = this->get_parameter("spin_threshold").as_double();
+
this->declare_parameter("max_dt_align", 0.3);
this->max_dt_align = this->get_parameter("max_dt_align").as_double();
@@ -95,17 +112,12 @@ FusionNode::FusionNode() : Node("fusion_node"){
void FusionNode::initCallback(const geometry_msgs::msg::PoseWithCovariance & init_msg){
- rclcpp::Clock clock;
- rclcpp::Time stamp = clock.now();
+ rclcpp::Time stamp = this->get_clock()->now();
this->init_state(0) = init_msg.pose.position.x;
this->init_state(1) = init_msg.pose.position.y;
this->init_state(2) = utils::qua2yaw(init_msg.pose.orientation);
- this->init_rot << cos(this->init_state(2)), -sin(this->init_state(2)), 0,
- sin(this->init_state(2)), cos(this->init_state(2)), 0,
- 0, 0, 1;
-
Eigen::Matrix3d init_cov;
init_cov << init_msg.covariance[0], 0, 0,
0, init_msg.covariance[7], 0,
@@ -130,7 +142,7 @@ void FusionNode::initCallback(const geometry_msgs::msg::PoseWithCovariance & ini
void FusionNode::localCallback(const nav_msgs::msg::Odometry & local_msg){
rclcpp::Time stamp = local_msg.header.stamp;
- this->prev_pred_time = stamp.seconds()+stamp.nanoseconds()*1e-9;
+ this->prev_pred_time = stamp.nanoseconds()*1e-9;
Eigen::Vector3d local_pose;
double local_yaw = utils::qua2yaw(local_msg.pose.pose.orientation);
@@ -146,19 +158,42 @@ void FusionNode::localCallback(const nav_msgs::msg::Odometry & local_msg){
0, local_msg.pose.covariance[7], 0,
0, 0, local_msg.pose.covariance[35];
- Eigen::Vector3d predicted_pose = this->init_state + this->init_rot*local_pose;
- ekf.Xprediction(predicted_pose, this->local_cov);
-
- Eigen::Vector3d robot_pose = ekf.getPose();
- Eigen::Matrix3d robot_cov = ekf.getCov();
+ try{
+ geometry_msgs::msg::TransformStamped tf = tf_buffer->lookupTransform(this->global_frame, this->robot_parent_frame, tf2::TimePointZero);
- pubFinalPose(stamp, robot_pose, robot_cov);
+ Eigen::Vector3d tf_vec;
+
+ tf_vec(0) = tf.transform.translation.x;
+ tf_vec(1) = tf.transform.translation.y;
+ tf_vec(2) = utils::qua2yaw(tf.transform.rotation);
+
+ Eigen::Matrix3d tf_rot;
+ tf_rot << cos(tf_vec(2)), -sin(tf_vec(2)), 0,
+ sin(tf_vec(2)), cos(tf_vec(2)), 0,
+ 0, 0, 1;
+
+ Eigen::Vector3d predicted_pose = tf_vec + tf_rot*local_pose;
+ ekf.Xprediction(predicted_pose, this->local_cov);
+
+ Eigen::Vector3d robot_pose = ekf.getPose();
+ Eigen::Matrix3d robot_cov = ekf.getCov();
+
+ pubFinalPose(stamp, robot_pose, robot_cov);
+ }catch(const tf2::TransformException & ex){
+ RCLCPP_INFO(
+ this->get_logger(), "Could not transform %s to %s: %s",
+ this->global_frame.c_str(), this->robot_parent_frame.c_str(), ex.what());
+ return;
+ }
}
void FusionNode::globalCallback(const geometry_msgs::msg::PoseWithCovarianceStamped & global_msg){
if(this->pose_modes[static_cast(PoseEnum::GLOBAL)]==static_cast(ModeEnum::FREEZE)) return;
+ if(this->spin_control && this->local_twist(2)>this->spin_threshold) return;
+
+
rclcpp::Time stamp = global_msg.header.stamp;
@@ -167,6 +202,8 @@ void FusionNode::globalCallback(const geometry_msgs::msg::PoseWithCovarianceStam
double global_yaw = utils::qua2yaw(global_msg.pose.pose.orientation);
global_pose << global_msg.pose.pose.position.x, global_msg.pose.pose.position.y, global_yaw;
+
+ this->lidar_yaw = global_pose(2);
Eigen::Matrix3d global_cov;
global_cov << global_msg.pose.covariance[0], 0, 0,
@@ -175,16 +212,15 @@ void FusionNode::globalCallback(const geometry_msgs::msg::PoseWithCovarianceStam
// align timestamp of prediction and correction
if(if_align){
- rclcpp::Clock clock;
- rclcpp::Time stamp = clock.now();
- double corr_time = stamp.seconds()+stamp.nanoseconds()*1e-9;
- double dt_align = corr_time-this->prev_pred_time;
+ rclcpp::Time align_stamp = this->get_clock()->now();
+ double curr_time = align_stamp.nanoseconds()*1e-9;
+ double dt_align = curr_time-this->prev_pred_time;
if(dt_alignmax_dt_align && dt_align>this->min_dt_align)
ekf.Vprediction(this->local_twist, this->local_cov, dt_align);
}
- ekf.correction(global_pose, global_cov);
+ ekf.correction(global_pose, this->global_h, global_cov);
Eigen::Vector3d robot_pose = ekf.getPose();
@@ -198,19 +234,13 @@ void FusionNode::globalCallback(const geometry_msgs::msg::PoseWithCovarianceStam
robot_tf_msg.translation.z = 0;
robot_tf_msg.rotation = utils::yaw2qua(robot_pose(2));
- bool tf_available = utils::indirectUpdateTransform(
- *this->tf_static_broadcaster,
- *this->tf_buffer,
- rclcpp::Time(0),
- this->global_frame,
- this->robot_parent_frame,
- this->robot_frame,
- robot_tf_msg);
-
- if(!tf_available){
- RCLCPP_WARN(
- this->get_logger(), "Could not transform %s to %s",
- robot_frame.c_str(), robot_parent_frame.c_str());
+ std::pair tf_available = utils::indirectUpdateTransform(
+ *this->tf_static_broadcaster, *this->tf_buffer, stamp, this->global_frame, this->robot_parent_frame, this->robot_frame, robot_tf_msg);
+
+ if(!tf_available.first){
+ RCLCPP_INFO(
+ this->get_logger(), "%s",
+ tf_available.second.c_str());
}
}
@@ -226,20 +256,19 @@ void FusionNode::cbCameraCallback(const geometry_msgs::msg::PoseStamped & cbcam_
double cbcam_yaw = utils::qua2yaw(cbcam_msg.pose.orientation);
- cbcam_pose << cbcam_msg.pose.position.x, cbcam_msg.pose.position.y, cbcam_yaw;
+ cbcam_pose << cbcam_msg.pose.position.x, cbcam_msg.pose.position.y, this->lidar_yaw;
// align timestamp of prediction and correction
if(if_align){
- rclcpp::Clock clock;
- rclcpp::Time stamp = clock.now();
- double corr_time = stamp.seconds()+stamp.nanoseconds()*1e-9;
- double dt_align = corr_time-this->prev_pred_time;
+ rclcpp::Time align_stamp = this->get_clock()->now();
+ double curr_time = align_stamp.nanoseconds()*1e-9;
+ double dt_align = curr_time-this->prev_pred_time;
if(dt_alignmax_dt_align && dt_align>this->min_dt_align)
ekf.Vprediction(this->local_twist, this->local_cov, dt_align);
}
- ekf.correction(cbcam_pose, this->cbcam_cov);
+ ekf.correction(cbcam_pose, this->cbcam_h, this->cbcam_cov);
Eigen::Vector3d robot_pose = ekf.getPose();
@@ -253,19 +282,13 @@ void FusionNode::cbCameraCallback(const geometry_msgs::msg::PoseStamped & cbcam_
robot_tf_msg.translation.z = 0;
robot_tf_msg.rotation = utils::yaw2qua(robot_pose(2));
- bool tf_available = utils::indirectUpdateTransform(
- *this->tf_static_broadcaster,
- *this->tf_buffer,
- stamp,
- this->global_frame,
- this->robot_parent_frame,
- this->robot_frame,
- robot_tf_msg);
-
- if(!tf_available){
- RCLCPP_WARN(
- this->get_logger(), "Could not transform %s to %s",
- robot_frame.c_str(), robot_parent_frame.c_str());
+ std::pair tf_available = utils::indirectUpdateTransform(
+ *this->tf_static_broadcaster, *this->tf_buffer, stamp, this->global_frame, this->robot_parent_frame, this->robot_frame, robot_tf_msg);
+
+ if(!tf_available.first){
+ RCLCPP_INFO(
+ this->get_logger(), "%s",
+ tf_available.second.c_str());
}
}
@@ -281,20 +304,19 @@ void FusionNode::obCameraCallback(const geometry_msgs::msg::PoseStamped & obcam_
double obcam_yaw = utils::qua2yaw(obcam_msg.pose.orientation);
- obcam_pose << obcam_msg.pose.position.x, obcam_msg.pose.position.y, obcam_yaw;
+ obcam_pose << obcam_msg.pose.position.x, obcam_msg.pose.position.y, this->lidar_yaw;
// align timestamp of prediction and correction
if(if_align){
- rclcpp::Clock clock;
- rclcpp::Time stamp = clock.now();
- double corr_time = stamp.seconds()+stamp.nanoseconds()*1e-9;
- double dt_align = corr_time-this->prev_pred_time;
+ rclcpp::Time align_stamp = this->get_clock()->now();
+ double curr_time = align_stamp.nanoseconds()*1e-9;
+ double dt_align = curr_time-this->prev_pred_time;
if(dt_alignmax_dt_align && dt_align>this->min_dt_align)
ekf.Vprediction(this->local_twist, this->local_cov, dt_align);
}
- ekf.correction(obcam_pose, this->obcam_cov);
+ ekf.correction(obcam_pose, this->obcam_h, this->obcam_cov);
Eigen::Vector3d robot_pose = ekf.getPose();
@@ -308,19 +330,13 @@ void FusionNode::obCameraCallback(const geometry_msgs::msg::PoseStamped & obcam_
robot_tf_msg.translation.z = 0;
robot_tf_msg.rotation = utils::yaw2qua(robot_pose(2));
- bool tf_available = utils::indirectUpdateTransform(
- *this->tf_static_broadcaster,
- *this->tf_buffer,
- stamp,
- this->global_frame,
- this->robot_parent_frame,
- this->robot_frame,
- robot_tf_msg);
-
- if(!tf_available){
- RCLCPP_WARN(
- this->get_logger(), "Could not transform %s to %s",
- robot_frame.c_str(), robot_parent_frame.c_str());
+ std::pair tf_available = utils::indirectUpdateTransform(
+ *this->tf_static_broadcaster, *this->tf_buffer, stamp, this->global_frame, this->robot_parent_frame, this->robot_frame, robot_tf_msg);
+
+ if(!tf_available.first){
+ RCLCPP_INFO(
+ this->get_logger(), "%s",
+ tf_available.second.c_str());
}
}
diff --git a/devel/core_algorithm/global/lidar_localization/CMakeLists.txt b/devel/core_algorithm/global/lidar_localization/CMakeLists.txt
index f4b4f59..231d527 100644
--- a/devel/core_algorithm/global/lidar_localization/CMakeLists.txt
+++ b/devel/core_algorithm/global/lidar_localization/CMakeLists.txt
@@ -33,8 +33,9 @@ install(PROGRAMS
DESTINATION lib/${PROJECT_NAME}
)
-install(
- DIRECTORY launch
+install(DIRECTORY
+ launch
+ param
DESTINATION share/${PROJECT_NAME}
)
diff --git a/devel/core_algorithm/global/lidar_localization/include/lidar_localization/beacon_finder.hpp b/devel/core_algorithm/global/lidar_localization/include/lidar_localization/beacon_finder.hpp
new file mode 100644
index 0000000..4572533
--- /dev/null
+++ b/devel/core_algorithm/global/lidar_localization/include/lidar_localization/beacon_finder.hpp
@@ -0,0 +1,7 @@
+#ifndef BEACON_FINDER_HPP_
+#define BEACON_FINDER_HPP_
+
+struct CoordStruct{
+ double x;
+ double y;
+};
\ No newline at end of file
diff --git a/devel/core_algorithm/global/lidar_localization/include/lidar_localization/lidar_localization_node.hpp b/devel/core_algorithm/global/lidar_localization/include/lidar_localization/lidar_localization_node.hpp
new file mode 100644
index 0000000..e08e796
--- /dev/null
+++ b/devel/core_algorithm/global/lidar_localization/include/lidar_localization/lidar_localization_node.hpp
@@ -0,0 +1,43 @@
+#ifndef LIDAR_LOCALIZATION_NODE_HPP_
+#define LIDAR_LOCALIZATION_NODE_HPP_
+
+#include "rclcpp/rclcpp.hpp"
+
+#include "obstacle_detector/msg/obstacle.hpp"
+#include "nav_msgs/msg/odometry.hpp"
+#include "geometry_msgs/msg/pose_with_covariance_stamped.hpp"
+#include "geometry_msgs/msg/pose_array.hpp"
+
+#include
+
+class LidarLocalizationNode : public rclcpp::Node{
+ public:
+ LidarNode();
+
+ void obstacleCallback(const obstacle_detector::msg::Obstacle &);
+ void predCallback(const nav_msgs::msg::Odometry &);
+
+ void pubGlobalPoser(rclcpp::Time, Eigen::Vector3d, Eigen::Matrix3d);
+ void pubBeacons();
+
+ private:
+ rclcpp::Subscription obs_sub;
+ rclcpp::Subscription pred_sub;
+
+ rclcpp::Puslisher global_puse_pub;
+ rclcpp::Publisher beacons_pub;
+
+ std::string mode;
+ std::string global_frame;
+ std::string robot_frame;
+
+ std::list
+
+ double likelihood_threshold;
+ double consistency_threshold;
+ double lidar_fac;
+
+ double beacon_coord[3][2];
+}
+
+#endif //LIDAR_LOCALIZATION_NODE_HPP_
\ No newline at end of file
diff --git a/devel/core_algorithm/global/lidar_localization/include/lidar_localization/trilateration.hpp b/devel/core_algorithm/global/lidar_localization/include/lidar_localization/trilateration.hpp
new file mode 100644
index 0000000..e69de29
diff --git a/devel/core_algorithm/global/lidar_localization/launch/calibrator_launch.xml b/devel/core_algorithm/global/lidar_localization/launch/calibrator_launch.xml
deleted file mode 100644
index e319ef5..0000000
--- a/devel/core_algorithm/global/lidar_localization/launch/calibrator_launch.xml
+++ /dev/null
@@ -1,5 +0,0 @@
-
-
-
-
-
\ No newline at end of file
diff --git a/devel/core_algorithm/global/lidar_localization/launch/debug_visualize_launch.xml b/devel/core_algorithm/global/lidar_localization/launch/debug_visualize_launch.xml
deleted file mode 100644
index 977f540..0000000
--- a/devel/core_algorithm/global/lidar_localization/launch/debug_visualize_launch.xml
+++ /dev/null
@@ -1,32 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
\ No newline at end of file
diff --git a/devel/core_algorithm/global/lidar_localization/launch/lidar_localization.launch.xml b/devel/core_algorithm/global/lidar_localization/launch/lidar_localization.launch.xml
new file mode 100644
index 0000000..df93b7f
--- /dev/null
+++ b/devel/core_algorithm/global/lidar_localization/launch/lidar_localization.launch.xml
@@ -0,0 +1,35 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/devel/core_algorithm/global/lidar_localization/launch/radius_compensation_launch.xml b/devel/core_algorithm/global/lidar_localization/launch/radius_compensation_launch.xml
deleted file mode 100644
index 25ef3b3..0000000
--- a/devel/core_algorithm/global/lidar_localization/launch/radius_compensation_launch.xml
+++ /dev/null
@@ -1,20 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
\ No newline at end of file
diff --git a/devel/core_algorithm/global/lidar_localization/launch/view_obstacles_launch.xml b/devel/core_algorithm/global/lidar_localization/launch/view_obstacles_launch.xml
deleted file mode 100644
index facabd6..0000000
--- a/devel/core_algorithm/global/lidar_localization/launch/view_obstacles_launch.xml
+++ /dev/null
@@ -1,11 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
\ No newline at end of file
diff --git a/devel/core_algorithm/global/lidar_localization/param/lidar_localization.yaml b/devel/core_algorithm/global/lidar_localization/param/lidar_localization.yaml
new file mode 100644
index 0000000..f67f0ef
--- /dev/null
+++ b/devel/core_algorithm/global/lidar_localization/param/lidar_localization.yaml
@@ -0,0 +1,11 @@
+lidar_localization:
+ ros__parameters:
+ side: 0
+ debug_mode: false
+ visualize_candidate: true
+ w_likelihood_threshold: 0.85
+ w_consistency_threshold: 0.92
+ w_lidar_multiplier: 0.96
+ b_likelihood_threshold: 0.87
+ b_consistency_threshold: 0.93
+ b_lidar_multiplier: 0.993
\ No newline at end of file
diff --git a/devel/core_algorithm/global/lidar_localization/param/lidar_localization.yml b/devel/core_algorithm/global/lidar_localization/param/lidar_localization.yml
deleted file mode 100644
index eeeef19..0000000
--- a/devel/core_algorithm/global/lidar_localization/param/lidar_localization.yml
+++ /dev/null
@@ -1,8 +0,0 @@
-lidar_localization:
- ros__parameters:
- side: 0
- debug_mode: false
- visualize_candidate: true
- likelihood_threshold: 0.8
- consistency_threshold: 0.92
- lidar_multiplier: 0.987
\ No newline at end of file
diff --git a/devel/core_algorithm/global/lidar_localization/scripts/lidar_member_function.py b/devel/core_algorithm/global/lidar_localization/scripts/lidar_member_function.py
index 1934ae3..03c858d 100644
--- a/devel/core_algorithm/global/lidar_localization/scripts/lidar_member_function.py
+++ b/devel/core_algorithm/global/lidar_localization/scripts/lidar_member_function.py
@@ -19,43 +19,54 @@ def __init__(self):
super().__init__('lidar_localization_node')
# Declare parameters
- self.declare_parameter('side', 0)
+ self.declare_parameter('bot', 13)
+ self.declare_parameter('mode', 'yellow')
self.declare_parameter('debug_mode', False)
self.declare_parameter('use_two_beacons', False)
self.declare_parameter('visualize_candidate', True)
- self.declare_parameter('likelihood_threshold', 0.8)
- self.declare_parameter('consistency_threshold', 0.92)
self.declare_parameter('robot_frame_id', 'base_footprint')
- self.declare_parameter('robot_parent_frame_id', 'map')
- self.declare_parameter('lidar_multiplier', 0.987)
+ self.declare_parameter('global_frame_id', 'map')
+ self.declare_parameter('w_likelihood_threshold', 0.87)
+ self.declare_parameter('w_consistency_threshold', 0.93)
+ self.declare_parameter('w_lidar_multiplier', 0.87)
+ self.declare_parameter('b_likelihood_threshold', 0.87)
+ self.declare_parameter('b_consistency_threshold', 0.93)
+ self.declare_parameter('b_lidar_multiplier', 0.993)
self.declare_parameter('likelihood_threshold_two', 0.95)
self.declare_parameter('consistency_threshold_two', 0.99)
# Get parameters
- self.side = self.get_parameter('side').get_parameter_value().integer_value
+ self.bot = self.get_parameter('bot').get_parameter_value().integer_value
+ self.side = self.get_parameter('mode').get_parameter_value().string_value
self.debug_mode = self.get_parameter('debug_mode').get_parameter_value().bool_value
self.p_use_two_beacons = self.get_parameter('use_two_beacons').get_parameter_value().bool_value
self.visualize_true = self.get_parameter('visualize_candidate').get_parameter_value().bool_value
- self.likelihood_threshold = self.get_parameter('likelihood_threshold').get_parameter_value().double_value
- self.consistency_threshold = self.get_parameter('consistency_threshold').get_parameter_value().double_value
self.robot_frame_id = self.get_parameter('robot_frame_id').get_parameter_value().string_value
- self.robot_parent_frame_id = self.get_parameter('robot_parent_frame_id').get_parameter_value().string_value
- self.lidar_multiplier = self.get_parameter('lidar_multiplier').get_parameter_value().double_value
+ self.global_frame_id = self.get_parameter('global_frame_id').get_parameter_value().string_value
self.likelihood_threshold_two = self.get_parameter('likelihood_threshold_two').get_parameter_value().double_value
self.consistency_threshold_two = self.get_parameter('consistency_threshold_two').get_parameter_value().double_value
+ if self.bot == 11:
+ self.likelihood_threshold = self.get_parameter('w_likelihood_threshold').get_parameter_value().double_value
+ self.consistency_threshold = self.get_parameter('w_consistency_threshold').get_parameter_value().double_value
+ self.lidar_multiplier = self.get_parameter('w_lidar_multiplier').get_parameter_value().double_value
+ elif self.bot == 13:
+ self.likelihood_threshold = self.get_parameter('b_likelihood_threshold').get_parameter_value().double_value
+ self.consistency_threshold = self.get_parameter('b_consistency_threshold').get_parameter_value().double_value
+ self.lidar_multiplier = self.get_parameter('b_lidar_multiplier').get_parameter_value().double_value
+
# Set the landmarks map based on the side
- if self.side == 0:
+ if self.side == 'yellow':
self.landmarks_map = [
- np.array([-0.083, 0.041]),
- np.array([-0.083, 1.959]),
- np.array([3.083, 1.0])
+ np.array([-0.094, 0.057]),
+ np.array([-0.094, 1.943]),
+ np.array([3.094, 1.0])
]
- elif self.side == 1:
+ elif self.side == 'blue':
self.landmarks_map = [
- np.array([3.083, 0.041]),
- np.array([3.083, 1.959]),
- np.array([-0.083, 1.0])
+ np.array([3.094, 0.057]),
+ np.array([3.094, 1.943]),
+ np.array([-0.094, 1.0])
]
# set debug mode
@@ -132,7 +143,7 @@ def obstacle_callback(self, msg): # main
# check if TF is available. If true, use the TF. If false, use the latest topic
try:
self.predict_transform = self.tf_buffer.lookup_transform(
- self.robot_parent_frame_id,
+ self.global_frame_id,
self.robot_frame_id,
Time()
)
@@ -147,7 +158,7 @@ def obstacle_callback(self, msg): # main
)
])
except (LookupException, ConnectivityException, ExtrapolationException) as e:
- self.get_logger().error(f'Could not transform {self.robot_parent_frame_id} to {self.robot_frame_id}: {e}')
+ self.get_logger().error(f'Could not transform {self.global_frame_id} to {self.robot_frame_id}: {e}')
self.get_logger().debug("now try to use the latest topic")
if self.newPose == False:
self.get_logger().error("no new predict topic, skip.")
@@ -215,14 +226,14 @@ def set_lidar_side_callback(self, msg):
side = msg.data.lower()
if side in ['0', '1', 'yellow', 'blue']:
if side == '0' or side == 'yellow':
- self.side = 0
+ self.side = 'yellow'
self.landmarks_map = [
np.array([-0.083, 0.041]),
np.array([-0.083, 1.959]),
np.array([3.083, 1.0])
]
elif side == '1' or side == 'blue':
- self.side = 1
+ self.side = 'blue'
self.landmarks_map = [
np.array([3.083, 0.041]),
np.array([3.083, 1.959]),
@@ -276,8 +287,8 @@ def get_obs_candidate(self, landmark, obs_raw):
di_square = y.T @ S_inv @ y
likelihood = np.exp(-0.5 * di_square)
if likelihood > self.likelihood_threshold:
- obs[0] = 0.987*obs[0]
- obs[1] = 0.987*obs[1]
+ obs[0] = self.lidar_multiplier*obs[0]
+ obs[1] = self.lidar_multiplier*obs[1]
if likelihood > self.likelihood_threshold:
obs_candidates.append({'position': obs, 'probability': likelihood})
else:
@@ -478,11 +489,11 @@ def get_set_two(self, two_index):
# geometry consistency
# 1. check the cross product: 'robot to beacon 0' cross 'robot to beacon 1'
cross = np.cross(set['beacons'][0], set['beacons'][1]) # TODO: check if beacon 0 and 1 will be in the order of beacon a, b and c
- if self.side == 0: # yellow is clockwise(negative)
+ if self.side == 'yellow': # yellow is clockwise(negative)
if cross > 0:
# self.get_logger().debug("cross product is positive")
continue
- elif self.side == 1: # blue is counter-clockwise(positive)
+ elif self.side == 'blue': # blue is counter-clockwise(positive)
if cross < 0:
# self.get_logger().debug("cross product is negative")
continue
@@ -676,10 +687,10 @@ def get_geometry_consistency(self, beacons):
# if the index is not found in map, it is probably on the lower triangle of the matrix
# check the landmark sequence is correct, clockwise for yellow, counter-clockwise for blue
- if self.side == 0:
+ if self.side == 'yellow':
if np.cross(beacons[1] - beacons[0], beacons[2] - beacons[0]) > 0:
consistency = 0
- elif self.side == 1:
+ elif self.side == 'blue':
if np.cross(beacons[1] - beacons[0], beacons[2] - beacons[0]) < 0:
consistency = 0
diff --git a/devel/core_algorithm/global/lidar_localization/src/beacon_finder.cpp b/devel/core_algorithm/global/lidar_localization/src/beacon_finder.cpp
new file mode 100644
index 0000000..e69de29
diff --git a/devel/core_algorithm/global/lidar_localization/src/lidar_localization_node.cpp b/devel/core_algorithm/global/lidar_localization/src/lidar_localization_node.cpp
new file mode 100644
index 0000000..0b04f70
--- /dev/null
+++ b/devel/core_algorithm/global/lidar_localization/src/lidar_localization_node.cpp
@@ -0,0 +1,77 @@
+#include "lidar_localization/lidar_localization_node.hpp"
+
+LidarLocalizationNode::LidarLocalizationNode(){
+ this->tf_buffer = std::make_unique(this->get_clock());
+ this->tf_listener = std::make_shared(*tf_buffer);
+
+
+ this->declare_parameter("mode", "yellow");
+ this->mode = this->get_parameter("mode").as_string();
+
+ this->declare_parameter("global_frame_id", "map");
+ this->global_frame = this->get_parameter("global_frame_id").as_string();
+
+ this->declare_parameter("robot_frame_id", "base_footprint");
+ this->robot_frame = this->get_parameter("robot_frame_id").as_string();
+
+ this->declare_parameter("likelihood_threshold", 0.87);
+ double likelihood_threshold = this->get_parameter("likelihood_threshold").as_double();
+
+ this->declare_parameter("consistency_threshold", 0.93);
+ double consistency_threshold = this->get_parameter("consistency_threshold").as_double();
+
+ this->declare_parameter("lidar_multiplier", 0.987);
+ double lidar_fac = this->get_parameter("lidar_multiplier").as_double();
+
+ if(this->mode == "yellow"){
+ this->beacon_coord[0][0] = -0.083; this->beacon_coord[0][1] = 0.041;
+ this->beacon_coord[1][0] = -0.083; this->beacon_coord[1][1] = 1.959;
+ this->beacon_coord[2][0] = 3.083; this->beacon_coord[2][1] = 1.0;
+ }
+ else if(this->mode == "blue"){
+ this->beacon_coord[0][0] = 3.083; this->beacon_coord[0][1] = 0.041;
+ this->beacon_coord[1][0] = 3.083; this->beacon_coord[1][1] = 1.959;
+ this->beacon_coord[2][0] = -0.083; this->beacon_coord[2][1] = 1.0;
+ }
+
+
+ this->obs_sub = this->create_subscription(
+ "raw_obstacles", 10, std::bind(&LidarLocalizationNode::obstacleCallback, this, std::placeholders::_1));
+
+ this->pred_sub = this->create_subscription(
+ "final_pose", 10, std::bind(&LidarLocalizationNode::predCallback, this, std::placeholders::_1));
+
+
+ this->global_pose_pub = this->create_publisher("global_pose", 10);
+
+ this->beacons_pub = this->create_publisher("beacons", 10);
+}
+
+LidarLocalizationNode::obstacleCallback(const obstacle_detector::msg::Obstacles & obs_msg){
+ // assign obstacle coordinates to linked list
+ int circles_len = sizeof(obs_msg.circles)/sizeof(obs_msg.circles[0]);
+ for(int i=0; i());
+ rclcpp::shutdown();
+
+ return 0;
+}
\ No newline at end of file
diff --git a/devel/core_algorithm/global/lidar_localization/src/trilateration.cpp b/devel/core_algorithm/global/lidar_localization/src/trilateration.cpp
new file mode 100644
index 0000000..e69de29
diff --git a/devel/core_algorithm/local/imu_drive/launch/imu_drive_firm.xml b/devel/core_algorithm/local/imu_drive/launch/imu_drive_firm.xml
index 0015644..1b25bae 100644
--- a/devel/core_algorithm/local/imu_drive/launch/imu_drive_firm.xml
+++ b/devel/core_algorithm/local/imu_drive/launch/imu_drive_firm.xml
@@ -19,7 +19,6 @@
-
diff --git a/devel/core_algorithm/local/wheel_inertial_odometry/CMakeLists.txt b/devel/core_algorithm/local/wheel_inertial_odometry/CMakeLists.txt
index d8e1260..599b777 100644
--- a/devel/core_algorithm/local/wheel_inertial_odometry/CMakeLists.txt
+++ b/devel/core_algorithm/local/wheel_inertial_odometry/CMakeLists.txt
@@ -60,6 +60,7 @@ install(DIRECTORY
install(DIRECTORY
launch
+ param
DESTINATION share/${PROJECT_NAME}
)
diff --git a/devel/core_algorithm/local/wheel_inertial_odometry/include/wheel_inertial_odometry/wio_node.hpp b/devel/core_algorithm/local/wheel_inertial_odometry/include/wheel_inertial_odometry/wio_node.hpp
index 44ef358..beb5253 100644
--- a/devel/core_algorithm/local/wheel_inertial_odometry/include/wheel_inertial_odometry/wio_node.hpp
+++ b/devel/core_algorithm/local/wheel_inertial_odometry/include/wheel_inertial_odometry/wio_node.hpp
@@ -31,8 +31,6 @@ class WioNode : public rclcpp::Node{
std::string robot_parent_frame;
std::string robot_frame;
- Eigen::Vector3d prev_wheel_pose;
- Eigen::Vector3d d_position;
Eigen::Vector3d local_pose;
Eigen::Vector3d local_twist;
Eigen::Matrix3d local_pose_cov;
diff --git a/devel/core_algorithm/local/wheel_inertial_odometry/launch/local.launch.py b/devel/core_algorithm/local/wheel_inertial_odometry/launch/local.launch.py
deleted file mode 100644
index 5450190..0000000
--- a/devel/core_algorithm/local/wheel_inertial_odometry/launch/local.launch.py
+++ /dev/null
@@ -1,81 +0,0 @@
-from launch import LaunchDescription
-from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
-from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
-from launch.launch_description_sources import PythonLaunchDescriptionSource, AnyLaunchDescriptionSource
-from launch_ros.actions import Node
-from launch_ros.substitutions import FindPackageShare
-
-def generate_launch_description():
- robot_name = LaunchConfiguration('robot_name')
- robot_name_slash = LaunchConfiguration('robot_name_slash')
- imu_param = LaunchConfiguration('imu_param')
- simulation = LaunchConfiguration('simulation')
- linear_velocity_threshold = LaunchConfiguration('linear_velocity_threshold')
- angular_velocity_threshold = LaunchConfiguration('angular_velocity_threshold')
- robot_parent_frame_id = LaunchConfiguration('robot_parent_frame_id')
- robot_frame_id = LaunchConfiguration('robot_frame_id')
- vx_coeff = LaunchConfiguration('vx_coeff')
- vy_coeff = LaunchConfiguration('vy_coeff')
- w_coeff = LaunchConfiguration('w_coeff')
- x_cov_min = LaunchConfiguration('x_cov_min')
- y_cov_min = LaunchConfiguration('y_cov_min')
- theta_cov_min = LaunchConfiguration('theta_cov_min')
-
- declare_args = [
- DeclareLaunchArgument('robot_name', default_value='robot'),
- DeclareLaunchArgument('robot_name_slash', default_value='robot/'),
- DeclareLaunchArgument('imu_param', default_value='0'),
- DeclareLaunchArgument('simulation', default_value='false'),
- DeclareLaunchArgument('linear_velocity_threshold', default_value='2.0'),
- DeclareLaunchArgument('angular_velocity_threshold', default_value='6.0'),
- DeclareLaunchArgument('robot_parent_frame_id', default_value='odom'),
- DeclareLaunchArgument('robot_frame_id', default_value='base_footprint'),
- DeclareLaunchArgument('vx_coeff', default_value='0.3'),
- DeclareLaunchArgument('vy_coeff', default_value='0.3'),
- DeclareLaunchArgument('w_coeff', default_value='2.0'),
- DeclareLaunchArgument('x_cov_min', default_value='6.25e-4'),
- DeclareLaunchArgument('y_cov_min', default_value='6.25e-4'),
- DeclareLaunchArgument('theta_cov_min', default_value='0.08'),
- ]
-
- # IMU firmware and covariance feedback loop node (contain IMU spatial launch)
- imu_drive_launch_path = PathJoinSubstitution([
- FindPackageShare('imu_drive'),
- 'launch',
- 'imu_drive_firm.xml'
- ])
-
- imu_drive_launch = IncludeLaunchDescription(
- AnyLaunchDescriptionSource(imu_drive_launch_path),
- launch_arguments={
- 'robot_name': robot_name,
- 'robot_name_slash': robot_name_slash,
- 'param': imu_param,
- 'simulation': simulation,
- }.items()
- )
-
- wio_node = Node(
- package='wheel_inertial_odometry',
- executable='wio_node',
- name='wio_node',
- parameters=[{
- 'linear_velocity_threshold': linear_velocity_threshold,
- 'angular_velocity_threshold': angular_velocity_threshold,
- 'robot_parent_frame_id': robot_parent_frame_id,
- 'robot_frame_id': robot_frame_id,
- 'vx_coeff': vx_coeff,
- 'vy_coeff': vy_coeff,
- 'w_coeff': w_coeff,
- 'x_cov_min': x_cov_min,
- 'y_cov_min': y_cov_min,
- 'theta_cov_min': theta_cov_min,
- }]
- )
-
- return LaunchDescription(
- declare_args + [
- wio_node,
- imu_drive_launch,
- ]
- )
\ No newline at end of file
diff --git a/devel/core_algorithm/local/wheel_inertial_odometry/launch/local.launch.xml b/devel/core_algorithm/local/wheel_inertial_odometry/launch/local.launch.xml
new file mode 100644
index 0000000..1e80adf
--- /dev/null
+++ b/devel/core_algorithm/local/wheel_inertial_odometry/launch/local.launch.xml
@@ -0,0 +1,28 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/devel/core_algorithm/local/wheel_inertial_odometry/launch/local_filter.xml b/devel/core_algorithm/local/wheel_inertial_odometry/launch/local_filter.xml
deleted file mode 100644
index 2894e42..0000000
--- a/devel/core_algorithm/local/wheel_inertial_odometry/launch/local_filter.xml
+++ /dev/null
@@ -1,39 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/devel/core_algorithm/local/wheel_inertial_odometry/launch/local_filter_whole.xml b/devel/core_algorithm/local/wheel_inertial_odometry/launch/local_filter_whole.xml
deleted file mode 100644
index 088f9a2..0000000
--- a/devel/core_algorithm/local/wheel_inertial_odometry/launch/local_filter_whole.xml
+++ /dev/null
@@ -1,63 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
\ No newline at end of file
diff --git a/devel/core_algorithm/local/wheel_inertial_odometry/launch/wio.launch.xml b/devel/core_algorithm/local/wheel_inertial_odometry/launch/wio.launch.xml
new file mode 100644
index 0000000..9b130a9
--- /dev/null
+++ b/devel/core_algorithm/local/wheel_inertial_odometry/launch/wio.launch.xml
@@ -0,0 +1,12 @@
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/devel/core_algorithm/local/wheel_inertial_odometry/param/local_filter.yaml b/devel/core_algorithm/local/wheel_inertial_odometry/param/local_filter.yaml
deleted file mode 100644
index aebf2a8..0000000
--- a/devel/core_algorithm/local/wheel_inertial_odometry/param/local_filter.yaml
+++ /dev/null
@@ -1,117 +0,0 @@
-
-/**:
- ros__parameters:
- frequency: 100
- silent_tf_failure: false
- sensor_timeout: 0.01
- two_d_mode: true
-
- smooth_lagged_data: false
- history_length: 0.4
-
- dynamic_process_noise_covariance: false
-
- predict_to_current_time: false
-
- print_diagnostics: false
-
- # debug
- debug: false
- debug_out_file: /path/to/debug/file.txt
-
- # frames
- map_frame: map
- odom_frame: odom
- base_link_frame: base_footprint
- world_frame: odom
- transform_time_offset: 0.05
- transform_timeout: 0
-
- # sensors
- # config: [x, y, z,
- # r, p, y,
- # x., y., z.,
- # r., p., y.,
- # x.., y.., z..]
- odom0: odom
- odom0_config: [false, false, false,
- false, false, false,
- true, true, false,
- false, false, true,
- false, false, false]
- odom0_queue_size: 20
- odom0_differential: false
- odom0_relative: false
- odom0_nodelay: true
-
- odom0_twist_rejection_threshold: 100
-
- imu0: imu/data_cov
- imu0_config: [false, false, false,
- false, false, false,
- false, false, false,
- false, false, true,
- true, true, false]
- imu0_queue_size: 100
- imu0_differential: false
- imu0_relative: false
- imu0_nodelay: true
-
- imu0_twist_rejection_threshold: 1000000000000.0
- imu0_linear_acceleration_rejection_threshold: 1000000000000.0
-
- imu0_remove_gravitational_acceleration: false
-
-
- initial_state: [0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0]
-
- publish_tf: true
- publish_acceleration: true
-
- # control
- # acc_config: [x., y., z., r., p., y.]
- use_control: false
- stamped_control: false
- control_timeout: 0.2
- control_config: [true, true, false, false, false, true]
- acceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 3.4]
- deceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 4.5]
- acceleration_gains: [0.8, 0.0, 0.0, 0.0, 0.0, 0.9]
- deceleration_gains: [1.0, 0.0, 0.0, 0.0, 0.0, 1.0]
-
- # config: [x, y, z, r, p, y, x., y., z., r., p., y., x.., y.., z..]
- process_noise_covariance: [0.005, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0.005, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0.006, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0.25, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0.25, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.2, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
-
- initial_estimate_covariance: [0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0.1, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-6, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9]
diff --git a/devel/core_algorithm/local/wheel_inertial_odometry/param/local_filter_whole.yaml b/devel/core_algorithm/local/wheel_inertial_odometry/param/local_filter_whole.yaml
deleted file mode 100644
index 0f870b5..0000000
--- a/devel/core_algorithm/local/wheel_inertial_odometry/param/local_filter_whole.yaml
+++ /dev/null
@@ -1,196 +0,0 @@
-# ---------------------------
-# -------- Rosserial --------
-# ---------------------------
-rosserial_server_dp:
- ros__parameters:
- port: "/dev/USB0-3" # not used?
-
-# ---------------------------
-# ------ Local filter ndoe ------
-# ---------------------------
-local_filter_LPF:
- ros__parameters:
- # Active this node
- active: true
-
- # Set publish to this node
- publish: true
-
- # Open param service
- update_params: false
-
- # Covariance for "const" part
- covariance_x: 0.001
- covariance_y: 0.001
- covariance_z: 0.001
- covariance_vx: 0.0042
- covariance_vy: 0.0042
- covariance_vz: 0.005
-
- # Covariance for "multiple" part
- covariance_multi_vx: 0.
- covariance_multi_vy: 0.
- covariance_multi_vz: 0.
-
- # Dynamic adjustment from :
- # True: (ns)/cmd_vel
- # False: (ns)/final_pose
- using_nav_vel_cb: false
-
- # Open if STM has integral information
- use_stm_integral: false
-
- # Open Dynamic reconfigure service
- using_dynamic_reconf: true
-
-# ----------------------
-# ------ IMU node ------
-# ----------------------
-imu_node:
- ros__parameters:
- # Set the usage of the node
- active: true
- publish: true
-
- # Open param service
- update_params: false
-
- # Covariance for "const" part
- covariance_vx: 0.005
- covariance_vy: 0.005
- covariance_vz: 0.001
- covariance_ax: 0.1
- covariance_ay: 0.1
- covariance_az: 0.1
-
- # Covariance for "multiple" part
- cov_multi_vel: 0.2
- cov_multi_acl: 0.2
-
- # Use which topic to dynamic adjust covariance
- using_nav_vel_cb: false
-
- # Low pass filter -> beleive previous
- filter_prev: 0.1
-
- using_dynamic_reconf: true
-
-# ----------------------
-# ------ EKF node ------
-# ----------------------
-ekf_velocity:
- ros__parameters:
- frequency: 100
- silent_tf_failure: false
- sensor_timeout: 0.01
- two_d_mode: true
-
- smooth_lagged_data: false
- history_length: 0.4
-
- dynamic_process_noise_covariance: false
-
- predict_to_current_time: false
-
- print_diagnostics: false
-
- # debug
- debug: false
- debug_out_file: /path/to/debug/file.txt
-
- # frames
- map_frame: map
- odom_frame: odom
- base_link_frame: base_footprint
- world_frame: odom
- transform_time_offset: 0.0
- transform_timeout: 0
-
- # sensors
- # config: [x, y, z,
- # r, p, y,
- # x., y., z.,
- # r., p., y.,
- # x.., y.., z..]
- odom0: odom
- odom0_config: [false, false, false,
- false, false, false,
- true, true, false,
- false, false, true,
- false, false, false]
- odom0_queue_size: 20
- odom0_differential: false
- odom0_relative: false
- odom0_nodelay: true
-
- odom0_twist_rejection_threshold: 100
-
- imu0: imu/data_cov
- imu0_config: [false, false, false,
- false, false, false,
- false, false, false,
- false, false, true,
- false, false, false]
- imu0_queue_size: 100
- imu0_differential: false
- imu0_relative: false
- imu0_nodelay: true
-
- imu0_twist_rejection_threshold: 1000000000000.0
- imu0_linear_acceleration_rejection_threshold: 1000000000000.0
-
- imu0_remove_gravitational_acceleration: false
-
-
- initial_state: [0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0]
-
- publish_tf: true
- publish_acceleration: true
-
- # control
- # acc_config: [x., y., z., r., p., y.]
- use_control: false
- stamped_control: false
- control_timeout: 0.2
- control_config: [true, true, false, false, false, true]
- acceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 3.4]
- deceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 4.5]
- acceleration_gains: [0.8, 0.0, 0.0, 0.0, 0.0, 0.9]
- deceleration_gains: [1.0, 0.0, 0.0, 0.0, 0.0, 1.0]
-
- # config: [x, y, z, r, p, y, x., y., z., r., p., y., x.., y.., z..]
- process_noise_covariance: [1e-6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 1e-6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 1e-6, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 1e-2, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 1e-2, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.1, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-3, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-3, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
-
- initial_estimate_covariance: [0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0.1, 0, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.1, 0, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-4, 0, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-4, 0,
- 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9]
diff --git a/devel/core_algorithm/local/wheel_inertial_odometry/param/wio.yaml b/devel/core_algorithm/local/wheel_inertial_odometry/param/wio.yaml
new file mode 100644
index 0000000..a54538e
--- /dev/null
+++ b/devel/core_algorithm/local/wheel_inertial_odometry/param/wio.yaml
@@ -0,0 +1,12 @@
+wio_node:
+ ros__parameters:
+ linear_velocity_threshold: 2.0
+ angular_velocity_threshold: 6.0
+
+ vx_coeff: 0.3
+ vy_coeff: 0.3
+ w_coeff: 2.0
+
+ x_cov_min: 1.67e-6
+ y_cov_min: 1.67e-6
+ theta_cov_min: 1.07e-4
\ No newline at end of file
diff --git a/devel/core_algorithm/local/wheel_inertial_odometry/src/wio_node.cpp b/devel/core_algorithm/local/wheel_inertial_odometry/src/wio_node.cpp
index d7d744a..1b1e916 100644
--- a/devel/core_algorithm/local/wheel_inertial_odometry/src/wio_node.cpp
+++ b/devel/core_algorithm/local/wheel_inertial_odometry/src/wio_node.cpp
@@ -15,8 +15,6 @@ WioNode::WioNode() : Node("wio_node"){
for(int i=0; i<3; i++) this->pose_cov_min[i] = 0;
this->first_odom_cb = true;
this->prev_odom_time = 0.0;
- this->prev_wheel_pose.setZero();
- this->d_position.setZero();
this->local_pose.setZero();
this->local_twist.setZero();
this->local_pose_cov.setIdentity();
@@ -75,13 +73,11 @@ WioNode::WioNode() : Node("wio_node"){
void WioNode::wheelCallback(const geometry_msgs::msg::Twist & wheel_msg)
{
- rclcpp::Clock clock;
- rclcpp::Time stamp = clock.now();
- double odom_time = stamp.seconds() + stamp.nanoseconds() * 1e-9;
-
+ rclcpp::Time stamp = this->get_clock()->now();
+ double odom_time = stamp.nanoseconds() * 1e-9;
+
if (this->first_odom_cb)
{
- this->prev_wheel_pose << wheel_msg.angular.x, wheel_msg.angular.y, 0.0;
this->prev_odom_time = odom_time;
this->first_odom_cb = false;
return;
@@ -90,13 +86,6 @@ void WioNode::wheelCallback(const geometry_msgs::msg::Twist & wheel_msg)
double dt = odom_time - this->prev_odom_time;
this->prev_odom_time = odom_time;
-
- this->d_position << wheel_msg.angular.x-this->prev_wheel_pose(0),
- wheel_msg.angular.y-this->prev_wheel_pose(1),
- 0.0;
-
- this->prev_wheel_pose << wheel_msg.angular.x, wheel_msg.angular.y, 0.0;
-
this->local_twist(0) = wheel_msg.linear.x;
this->local_twist(1) = wheel_msg.linear.y;
@@ -115,7 +104,7 @@ void WioNode::wheelCallback(const geometry_msgs::msg::Twist & wheel_msg)
void WioNode::imuCallback(const sensor_msgs::msg::Imu & imu_msg)
{
rclcpp::Time stamp = imu_msg.header.stamp;
- double time = stamp.seconds()+stamp.nanoseconds()*1e-9;
+ double time = stamp.nanoseconds()*1e-9;
if(this->first_imu_cb){
this->prev_imu_time = time;
@@ -126,18 +115,17 @@ void WioNode::imuCallback(const sensor_msgs::msg::Imu & imu_msg)
double dt = time-this->prev_imu_time;
this->prev_imu_time = time;
-
this->local_twist(2) = imu_msg.angular_velocity.z;
this->local_pose(2) =
- utils::angleNormalizing(this->local_pose(2)+0.5*this->local_twist(2)*dt);
+ utils::angleNormalizing(this->local_pose(2)+this->local_twist(2)*dt);
Eigen::Matrix3d R;
R << cos(this->local_pose(2)), -sin(this->local_pose(2)), 0.0,
sin(this->local_pose(2)), cos(this->local_pose(2)), 0.0,
0.0, 0.0, 0.0;
- this->local_pose += R*this->d_position;
+ this->local_pose += R*this->local_twist*dt;
// publish odometry
pubLocalPose(stamp);
diff --git a/devel/localization_bringup/CMakeLists.txt b/devel/localization_bringup/CMakeLists.txt
index 41f5781..39bab2e 100644
--- a/devel/localization_bringup/CMakeLists.txt
+++ b/devel/localization_bringup/CMakeLists.txt
@@ -24,8 +24,9 @@ install(TARGETS
DESTINATION lib/${PROJECT_NAME}
)
-install(
- DIRECTORY launch
+install(DIRECTORY
+ launch
+ param
DESTINATION share/${PROJECT_NAME}
)
diff --git a/devel/localization_bringup/launch/bag_test.launch.py b/devel/localization_bringup/launch/bag_test.launch.py
index aa7ab01..6ca83de 100644
--- a/devel/localization_bringup/launch/bag_test.launch.py
+++ b/devel/localization_bringup/launch/bag_test.launch.py
@@ -5,7 +5,7 @@
import yaml
def generate_launch_description():
- config_path='/home/user/localization-ws/src/core_algorithm/localization_bringup/param/bag_test.yaml'
+ config_path='/home/user/localization-ws/src/devel/localization_bringup/param/bag_test.yaml'
with open(config_path, 'r') as f:
cfg = yaml.safe_load(f)
@@ -19,7 +19,7 @@ def generate_launch_description():
remaps = []
for topic in play_pose_topics:
- remaps.append(f'{topic}:=/eurobot2025{topic}')
+ remaps.append(f'{topic}:=/pose_info{topic}')
actions = []
@@ -46,7 +46,7 @@ def generate_launch_description():
output='screen'
),
GroupAction([
- PushRosNamespace('eurobot2025'),
+ PushRosNamespace('pose_info'),
ExecuteProcess(
cmd=[
'ros2', 'bag', 'play',
diff --git a/devel/localization_bringup/launch/localization.launch.py b/devel/localization_bringup/launch/localization.launch.py
index 8a942ed..5e21eb7 100644
--- a/devel/localization_bringup/launch/localization.launch.py
+++ b/devel/localization_bringup/launch/localization.launch.py
@@ -7,41 +7,92 @@
def generate_launch_description():
+ offline = LaunchConfiguration('offline')
+ global_frame_id = LaunchConfiguration('global_frame_id')
+ robot_parent_frame_id = LaunchConfiguration('robot_parent_frame_id')
+ robot_frame_id = LaunchConfiguration('robot_frame_id')
+ bot = LaunchConfiguration('bot')
+ mode = LaunchConfiguration('mode')
rival_name = LaunchConfiguration('rival_name')
- # Declare arguments
- mode_arg = DeclareLaunchArgument(
- 'mode',
- default_value='yellow',
- description='Determine how to pubish initial pose'
- )
+ declare_args = [
+ DeclareLaunchArgument(
+ 'offline',
+ default_value='false'
+ ),
+ DeclareLaunchArgument(
+ 'global_frame_id',
+ default_value='map'
+ ),
+ DeclareLaunchArgument(
+ 'robot_parent_frame_id',
+ default_value='odom'
+ ),
+ DeclareLaunchArgument(
+ 'robot_frame_id',
+ default_value='base_footprint'
+ ),
+ DeclareLaunchArgument(
+ 'bot',
+ default_value='13'
+ ),
+ DeclareLaunchArgument(
+ 'mode',
+ default_value='yellow'
+ ),
+ DeclareLaunchArgument(
+ 'rival_name',
+ default_value='rival'
+ ),
+ ]
- mode = LaunchConfiguration('mode')
fusion_launch_path = PathJoinSubstitution([
- FindPackageShare('fusion'),
- 'launch',
+ FindPackageShare('fusion'),
+ 'launch',
'fusion.launch.xml'
])
local_launch_path = PathJoinSubstitution([
- FindPackageShare('wheel_inertial_odometry'),
- 'launch',
- 'local.launch.py'
+ FindPackageShare('wheel_inertial_odometry'),
+ 'launch',
+ 'local.launch.xml'
])
- ydlidar_launch = PathJoinSubstitution([
- FindPackageShare('lidar_localization'),
- 'launch',
- 'firmware',
- 'ydlidar_launch.py'
+ global_launch_path = PathJoinSubstitution([
+ FindPackageShare('lidar_localization'),
+ 'launch',
+ 'lidar_localization.launch.xml'
])
- obstacle_extractor_launch = PathJoinSubstitution([
- FindPackageShare('lidar_localization'),
- 'launch',
- 'obstacle_extractor_launch.xml'
- ])
+
+ fusion_launch = IncludeLaunchDescription(
+ AnyLaunchDescriptionSource(fusion_launch_path),
+ launch_arguments = {
+ 'global_frame_id': global_frame_id,
+ 'robot_parent_frame_id': robot_parent_frame_id,
+ 'robot_frame_id': robot_frame_id,
+ }.items()
+ )
+
+ local_launch = IncludeLaunchDescription(
+ AnyLaunchDescriptionSource(local_launch_path),
+ launch_arguments={
+ 'offline': offline,
+ 'robot_parent_frame_id': robot_parent_frame_id,
+ 'robot_frame_id': robot_frame_id,
+ }.items()
+ )
+
+ global_launch = IncludeLaunchDescription(
+ AnyLaunchDescriptionSource(global_launch_path),
+ launch_arguments={
+ 'bot': bot,
+ 'offline': offline,
+ 'mode': mode
+ }.items()
+ )
+
init_pose = Node(
package='localization_bringup',
@@ -49,30 +100,15 @@ def generate_launch_description():
name='pub_init',
output='screen',
parameters=[
- '/home/user/localization-ws/src/devel/localization_bringup/param/initial_pose.yaml',
+ PathJoinSubstitution([
+ FindPackageShare('localization_bringup'),
+ 'param',
+ 'initial_pose.yaml'
+ ]),
{'mode': mode}
]
)
- lidar_node = Node(
- package='lidar_localization',
- executable='lidar_member_function.py',
- name='lidar_localization_node',
- arguments=['--ros-args', '--log-level', 'info'],
- output='screen',
- parameters=[
- '/home/user/localization-ws/src/devel/core_algorithm/global/lidar_localization/param/lidar_localization.yml'
- ]
- )
-
- fusion_launch = IncludeLaunchDescription(
- AnyLaunchDescriptionSource(fusion_launch_path)
- )
-
- local_launch = IncludeLaunchDescription(
- AnyLaunchDescriptionSource(local_launch_path)
- )
-
rival_node = Node(
package='rival_localization',
executable='rival_localization',
@@ -144,34 +180,12 @@ def generate_launch_description():
]
)
- static_tf = Node(
- package='tf2_ros',
- executable='static_transform_publisher',
- name='robot_to_laser',
- output='screen',
- arguments=[
- '--x', '0', '--y', '0', '--z', '0',
- '--roll', '0', '--pitch', '0', '--yaw', '3.14',
- '--frame-id', 'base_footprint',
- '--child-frame-id', 'laser'
- ]
- )
-
- ydlidar_include = IncludeLaunchDescription(PythonLaunchDescriptionSource(ydlidar_launch))
- obstacle_extractor_include = IncludeLaunchDescription(AnyLaunchDescriptionSource(obstacle_extractor_launch))
-
return LaunchDescription([
- DeclareLaunchArgument('rival_name', default_value='rival'),
- DeclareLaunchArgument('side', default_value='0'),
-
- mode_arg,
- ydlidar_include,
- obstacle_extractor_include,
+ *declare_args,
TimerAction(period=0.5, actions=[init_pose]),
TimerAction(period=1.0, actions=[fusion_launch]),
- TimerAction(period=1.5, actions=[lidar_node]),
+ TimerAction(period=1.5, actions=[global_launch]),
TimerAction(period=2.0, actions=[local_launch]),
- TimerAction(period=2.5, actions=[rival_node, rival_obstacle_node]),
- TimerAction(period=3.0, actions=[static_tf])
+ TimerAction(period=2.5, actions=[rival_node, rival_obstacle_node])
])
\ No newline at end of file
diff --git a/devel/localization_bringup/param/bag_test.yaml b/devel/localization_bringup/param/bag_test.yaml
index 19fe214..a7de3a6 100644
--- a/devel/localization_bringup/param/bag_test.yaml
+++ b/devel/localization_bringup/param/bag_test.yaml
@@ -1,25 +1,28 @@
bag:
mode: play # record or play
- path: src/core_algorithm/localization_bringup/bag/
- name: test1
+ path: src/devel/localization_bringup/bag/
+ name: 0308_beacon_fail
record_topics:
- - /odoo_googoogoo
+ - /clock
+ - /tf
+ - /tf_static
+ - /wheel_pose
- /scan
- /raw_obstacles
- /imu/data_cov
- - /local_filter
+ - /local_pose
- /lidar_pose
- /final_pose
- /beacons_guaguagua
- /candidates
play_topics:
raw:
- - /odoo_googoogoo
+ - /clock
+ - /wheel_pose
- /scan
- - /raw_obstacles
- /imu/data_cov
result:
- - /local_filter
+ - /local_pose
- /lidar_pose
- /final_pose
- /beacons_guaguagua
diff --git a/devel/monitor/src/data_rate_test.cpp b/devel/monitor/src/data_rate_test.cpp
new file mode 100644
index 0000000..9d73eb1
--- /dev/null
+++ b/devel/monitor/src/data_rate_test.cpp
@@ -0,0 +1,95 @@
+#include "rclcpp/rclcpp.hpp"
+
+#include "geometry_msgs/msg/twist.hpp"
+#include "geometry_msgs/msg/pose_with_covariance_stamped.hpp"
+#include "sensor_msgs/msg/imu.hpp"
+#include "sensor_msgs/msg/laser_scan.hpp"
+
+class RateTest : public rclcpp::Node{
+ public:
+ RateTest(): Node("data_rate_test"){
+ this->wheel_sub = this->create_subscription(
+ "wheel_pose", 1, std::bind(&RateTest::wheelCallback, this, std::placeholders::_1));
+
+ this->imu_sub = this->create_subscription(
+ "imu/data_cov", 1, std::bind(&RateTest::imuCallback, this, std::placeholders::_1));
+
+ rclcpp::QoS qos(rclcpp::KeepLast(10));
+ qos.best_effort();
+ qos.durability_volatile();
+
+ this->scan_sub = this->create_subscription(
+ "scan", qos, std::bind(&RateTest::scanCallback, this, std::placeholders::_1));
+
+ this->global_sub = this->create_subscription(
+ "lidar_pose", 1, std::bind(&RateTest::globalCallback, this, std::placeholders::_1));
+
+
+ this->wheel_pub = this->create_publisher("slow_wheel_pose", 10);
+ this->imu_pub = this->create_publisher("slow_imu/data_cov", 10);
+ this->scan_pub = this->create_publisher("slow_scan", 10);
+ this->global_pub = this->create_publisher("slow_lidar_pose", 10);
+
+
+ this->declare_parameter("rate_fac", 1.0);
+ this->rate_fac = this->get_parameter("rate_fac").as_double();
+ }
+
+ void wheelCallback(const geometry_msgs::msg::Twist & wheel_msg){
+ this->wheel_count++;
+ if(this->wheel_count >= 1.0/this->rate_fac){
+ this->wheel_pub->publish(wheel_msg);
+ this->wheel_count = 0;
+ }
+ }
+
+ void imuCallback(const sensor_msgs::msg::Imu & imu_msg){
+ this->imu_count++;
+ if(this->imu_count >= 1.0/this->rate_fac){
+ this->imu_pub->publish(imu_msg);
+ this->imu_count = 0;
+ }
+ }
+
+ void scanCallback(const sensor_msgs::msg::LaserScan & scan_msg){
+ this->scan_count++;
+ if(this->scan_count >= 1.0/this->rate_fac){
+ this->scan_pub->publish(scan_msg);
+ this->scan_count = 0;
+ }
+ }
+
+ void globalCallback(const geometry_msgs::msg::PoseWithCovarianceStamped & global_msg){
+ this->global_count++;
+ if(this->global_count >= 1.0/this->rate_fac){
+ this->global_pub->publish(global_msg);
+ this->global_count = 0;
+ }
+ }
+
+ private:
+ rclcpp::Subscription::SharedPtr wheel_sub;
+ rclcpp::Subscription::SharedPtr imu_sub;
+ rclcpp::Subscription::SharedPtr scan_sub;
+ rclcpp::Subscription::SharedPtr global_sub;
+
+ rclcpp::Publisher::SharedPtr wheel_pub;
+ rclcpp::Publisher::SharedPtr imu_pub;
+ rclcpp::Publisher::SharedPtr scan_pub;
+ rclcpp::Publisher::SharedPtr global_pub;
+
+ double rate_fac = 0.0;
+
+ int wheel_count = 0;
+ int imu_count = 0;
+ int scan_count = 0;
+ int global_count = 0;
+};
+
+int main(int argc, char * argv[]){
+ rclcpp::init(argc, argv);
+ auto node = std::make_shared();
+ rclcpp::spin(node);
+ rclcpp::shutdown();
+ return 0;
+}
\ No newline at end of file
diff --git a/devel/utils/include/utils/gen_functs.hpp b/devel/utils/include/utils/gen_functs.hpp
index b4da4e0..98fb181 100644
--- a/devel/utils/include/utils/gen_functs.hpp
+++ b/devel/utils/include/utils/gen_functs.hpp
@@ -7,6 +7,8 @@
#include "tf2_ros/transform_broadcaster.h"
#include "tf2_ros/static_transform_broadcaster.h"
+#include
+
namespace utils
{
@@ -17,6 +19,7 @@ geometry_msgs::msg::Quaternion yaw2qua(double);
void updateStaticTransform(tf2_ros::StaticTransformBroadcaster &, rclcpp::Time, std::string, std::string, geometry_msgs::msg::Transform);
void updateTransform(tf2_ros::TransformBroadcaster &, rclcpp::Time, std::string, std::string, geometry_msgs::msg::Transform);
-bool indirectUpdateTransform(tf2_ros::StaticTransformBroadcaster &, tf2_ros::Buffer &, rclcpp::Time, std::string, std::string, std::string, geometry_msgs::msg::Transform);
+
+std::pair indirectUpdateTransform(tf2_ros::StaticTransformBroadcaster &, tf2_ros::Buffer &, rclcpp::Time, std::string, std::string, std::string, geometry_msgs::msg::Transform);
}
\ No newline at end of file
diff --git a/devel/utils/src/gen_functs.cpp b/devel/utils/src/gen_functs.cpp
index 19bf962..d8a0c90 100644
--- a/devel/utils/src/gen_functs.cpp
+++ b/devel/utils/src/gen_functs.cpp
@@ -2,6 +2,8 @@
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
+#include
+
namespace utils
{
@@ -13,12 +15,14 @@ double qua2yaw(geometry_msgs::msg::Quaternion q){
tf2::Quaternion qua(q.x, q.y, q.z, q.w);
double _, yaw;
tf2::Matrix3x3(qua).getRPY(_, _, yaw);
+ angleNormalizing(yaw);
return yaw;
}
geometry_msgs::msg::Quaternion yaw2qua(double yaw){
tf2::Quaternion qua;
qua.setRPY(0, 0, yaw);
+ qua.normalize();
return tf2::toMsg(qua);
}
@@ -59,14 +63,16 @@ void updateTransform(
* TF tree: A->B->C. Update TF of AB using AB = AC * BC^-1.
* A: from_frame, B: to_frame, C: by_frame, TF of AC: tf_msg.
*/
-bool indirectUpdateTransform(
- tf2_ros::StaticTransformBroadcaster & static_tf_br,
+std::pair indirectUpdateTransform(
+ tf2_ros::StaticTransformBroadcaster & tf_br,
tf2_ros::Buffer & tf_buf,
- rclcpp::Time stamp,
+ rclcpp::Time stamp,
std::string from_frame,
std::string to_frame,
std::string by_frame,
geometry_msgs::msg::Transform tf_msg){
+ std::pair result(true, "");
+
geometry_msgs::msg::TransformStamped from2to_tf_msg;
from2to_tf_msg.header.stamp = stamp;
@@ -81,20 +87,22 @@ bool indirectUpdateTransform(
geometry_msgs::msg::TransformStamped to2by_tf_msg;
try{
- to2by_tf_msg = tf_buf.lookupTransform(to_frame, by_frame, stamp);
- } catch (const tf2::TransformException & ex) {
- return false;
- }
- tf2::fromMsg(to2by_tf_msg.transform, to2by_tf);
+ to2by_tf_msg = tf_buf.lookupTransform(to_frame, by_frame, stamp, tf2::durationFromSec(0.05));
+
+ tf2::fromMsg(to2by_tf_msg.transform, to2by_tf);
- tf2::Transform from2to_tf;
- from2to_tf = from2by_tf*to2by_tf.inverse();
+ tf2::Transform from2to_tf;
+ from2to_tf = from2by_tf*to2by_tf.inverse();
- from2to_tf_msg.transform = tf2::toMsg(from2to_tf);
+ from2to_tf_msg.transform = tf2::toMsg(from2to_tf);
- static_tf_br.sendTransform(from2to_tf_msg);
+ tf_br.sendTransform(from2to_tf_msg);
+ } catch (const tf2::TransformException & ex) {
+ result.first = false;
+ result.second = "Could not get transform " + to_frame + " to " + by_frame + ": " + ex.what();
+ }
- return true;
+ return result;
}
}
\ No newline at end of file
diff --git a/docker/.env b/docker/.env
index d7ae865..7acbc4a 100644
--- a/docker/.env
+++ b/docker/.env
@@ -6,8 +6,9 @@ COMPOSE_FILE=docker-compose.yaml
ROS_DOMAIN_ID=13
## Release version
-COMPOSE_PROFILES = communication, onboard-running
+COMPOSE_PROFILES = onboard-running
USER_UID=1004
+MODE=yellow
## Simply on local machine
# COMPOSE_PROFILES=local-developing
diff --git a/docker/Dockerfile.communication b/docker/Dockerfile.communication
deleted file mode 100644
index f291f25..0000000
--- a/docker/Dockerfile.communication
+++ /dev/null
@@ -1,75 +0,0 @@
-FROM ubuntu:22.04 AS base
-
-LABEL maintainer="Yu Hsiang Chen"
-LABEL email="seanchen1117@gmail.com"
-
-ENV DEBIAN_FRONTEND=noninteractive
-
-# Keep apt cache to speed up subsequent builds
-RUN rm -f /etc/apt/apt.conf.d/docker-clean; echo 'Binary::apt::APT::Keep-Downloaded-Packages "true";' > /etc/apt/apt.conf.d/keep-cache
-
-# Install common tools
-RUN --mount=type=cache,target=/var/cache/apt,sharing=private \
- apt-get update && apt-get install -y \
- curl \
- git \
- sudo \
- usbutils \
- v4l-utils \
- htop \
- iputils-ping \
- wget \
- net-tools \
- tmux \
- vim \
- wget \
- && rm -rf /var/lib/apt/lists/*
-
-FROM base AS build
-
-ENV DEBIAN_FRONTEND=noninteractive
-
-RUN rm -f /etc/apt/apt.conf.d/docker-clean; echo 'Binary::apt::APT::Keep-Downloaded-Packages "true";' > /etc/apt/apt.conf.d/keep-cache
-
-# Install ROS 2 Humble
-COPY modules/install_ros_humble.sh /tmp/install_ros_humble.sh
-RUN --mount=type=cache,target=/var/cache/apt,sharing=private \
- /tmp/install_ros_humble.sh && rm /tmp/install_ros_humble.sh
-
-# Install ROS Noetic
-# ref: https://docs.ros.org/en/humble/How-To-Guides/Using-ros1_bridge-Jammy-upstream.html
-# ref: https://github.com/osrf/docker_images/issues/635#issuecomment-1217505552
-# If there is still issue, try to comment the command below and enter the container to see the correct file name under /etc/apt/sources.list.d/
-RUN rm -rf /etc/apt/sources.list.d/ros2.sources
-RUN --mount=type=cache,target=/var/cache/apt,sharing=private \
- apt-get update \
- && apt remove -y python3-catkin-pkg python3-catkin-pkg-modules\
- && apt-get install -q -y --no-install-recommends ros-core-dev \
- && rm -rf /var/lib/apt/lists/*
-
-# Install ros1_bridge
-WORKDIR /ros2_humble
-COPY modules/install_ros_bridge.sh /tmp/install_ros_bridge.sh
-RUN --mount=type=cache,target=/var/cache/apt,sharing=private \
- /tmp/install_ros_bridge.sh && rm /tmp/install_ros_bridge.sh
-
-ENTRYPOINT []
-CMD ["/bin/bash"]
-
-FROM base AS deploy
-
-ENV DEBIAN_FRONTEND=noninteractive
-
-RUN rm -f /etc/apt/apt.conf.d/docker-clean; echo 'Binary::apt::APT::Keep-Downloaded-Packages "true";' > /etc/apt/apt.conf.d/keep-cache
-
-RUN --mount=type=cache,target=/var/cache/apt,sharing=private \
- apt-get update && apt-get install -y \
- libspdlog-dev \
- python3-packaging \
- ros-core-dev
-
-RUN mkdir -p /ros2_humble
-COPY --from=build /ros2_humble/install /ros2_humble/install
-
-ENTRYPOINT [ ]
-CMD ["/bin/bash"]
\ No newline at end of file
diff --git a/docker/docker-compose.yaml b/docker/docker-compose.yaml
index 339f5ca..02d2d94 100644
--- a/docker/docker-compose.yaml
+++ b/docker/docker-compose.yaml
@@ -26,6 +26,9 @@ x-common-vars: &ros2-vars
- /dev:/dev
# Mount workspace
- ../devel:/home/user/localization-ws/src/devel
+ - ../colcon/build:/home/user/localization-ws/build
+ - ../colcon/install:/home/user/localization-ws/install
+ - ../colcon/log:/home/user/localization-ws/log
services:
localization-devel:
@@ -57,83 +60,7 @@ services:
- *ros2-vars
command: /bin/bash -c "
source /opt/ros/humble/setup.bash &&
- colcon build"
-
- # containers for comunicating with firmware
- ros-core:
- profiles: ['communication']
- image: ros:noetic-ros-base
- container_name: ros-core
- privileged: true
- network_mode: host
- stdin_open: true
- tty: true
- working_dir: /
- stop_grace_period: 1s
- healthcheck:
- # The healthcheck is required for ros1-bridge to wait until roscore is ready.
- test: /ros_entrypoint.sh bash -c "rostopic list || exit 1"
- interval: 3s
- timeout: 10s
- retries: 5
- volumes:
- - /etc/timezone:/etc/timezone:ro
- - /etc/localtime:/etc/localtime:ro
- - /dev/dri:/dev/dri
- - /dev/shm:/dev/shm
- command: bash -c "source /opt/ros/noetic/setup.bash
- && roscore"
-
- ros1bridge:
- profiles: ['communication']
- build:
- context: .
- dockerfile: Dockerfile.communication
- target: deploy
- image: cyhsiang/dit-ros1bridge:latest
- container_name: ros1bridge
- privileged: true
- network_mode: host
- stdin_open: true
- tty: true
- working_dir: /
- depends_on:
- ros-core:
- # The healthcheck is required for ros1-bridge to wait until roscore is ready.
- condition: service_healthy
- environment:
- - ROS_LOCALHOST_ONLY=0
- - ROS_DOMAIN_ID=${ROS_DOMAIN_ID}
- - RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
-
- volumes:
- - /etc/timezone:/etc/timezone:ro
- - /etc/localtime:/etc/localtime:ro
- - /dev/dri:/dev/dri
- - /dev/shm:/dev/shm
- command: bash -c "source /ros2_humble/install/setup.bash
- && source /ros2_humble/install/ros1_bridge/share/ros1_bridge/local_setup.bash
- && export ROS_MASTER_URI=http://localhost:11311
- && ros2 run ros1_bridge dynamic_bridge 2>/dev/null"
-
- ros1:
- profiles: ['communication']
- image: osrf/ros:noetic-desktop-full
- container_name: ros1
- stdin_open: true
- tty: true
- network_mode: host
- privileged: true
- volumes:
- - /etc/timezone:/etc/timezone:ro
- - /etc/localtime:/etc/localtime:ro
- - /dev/dri:/dev/dri
- - /dev/shm:/dev/shm
- - ../docker/sensor_dep_ros1:/home/user/ros1-ws/src
- stop_grace_period: 1s
- command: /bin/bash -c "
- source /opt/ros/noetic/setup.bash &&
- cd /home/user/ros1-ws &&
- catkin_make &&
- source devel/setup.bash &&
- roslaunch firmware_comm firmware_comm.launch"
\ No newline at end of file
+ cd /home/user/localization-ws &&
+ colcon build &&
+ source install/setup.bash &&
+ ros2 launch localization_bringup localization.launch.py bot:=${ROS_DOMAIN_ID} mode:=${MODE}"
\ No newline at end of file
diff --git a/docker/modules/install_ros_bridge.sh b/docker/modules/install_ros_bridge.sh
deleted file mode 100644
index 7e2f1b7..0000000
--- a/docker/modules/install_ros_bridge.sh
+++ /dev/null
@@ -1,20 +0,0 @@
-#!/bin/bash
-set -e
-
-echo "Installing ROS Bridge..."
-
-apt update && apt install -y git
-
-# Create a workspace for the ros1_bridge
-mkdir -p src/ros1_bridge/src \
- && cd src/ros1_bridge/src \
- && git clone https://github.com/ros2/ros1_bridge \
- && cd /ros2_humble
-
-# Source the ROS 2 workspace
-source install/setup.bash
-
-# Build
-colcon build --packages-select ros1_bridge --cmake-force-configure
-
-echo "ROS Bridge installation completed successfully!"
\ No newline at end of file
diff --git a/docker/modules/install_ros_humble.sh b/docker/modules/install_ros_humble.sh
deleted file mode 100644
index 9985ca5..0000000
--- a/docker/modules/install_ros_humble.sh
+++ /dev/null
@@ -1,51 +0,0 @@
-#!/bin/bash
-set -e
-
-echo "Installing ROS Humble from source..."
-
-# Ref: https://docs.ros.org/en/humble/Installation/Alternatives/Ubuntu-Development-Setup.html
-# Set locale
-apt update && apt install -y locales
-locale-gen en_US en_US.UTF-8
-update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8
-export LANG=en_US.UTF-8
-
-# Setup sources
-apt install -y software-properties-common
-add-apt-repository universe
-
-apt update && apt install curl -y
-export ROS_APT_SOURCE_VERSION=$(curl -s https://api.github.com/repos/ros-infrastructure/ros-apt-source/releases/latest | grep -F "tag_name" | awk -F\" '{print $4}')
-curl -L -o /tmp/ros2-apt-source.deb "https://github.com/ros-infrastructure/ros-apt-source/releases/download/${ROS_APT_SOURCE_VERSION}/ros2-apt-source_${ROS_APT_SOURCE_VERSION}.$(. /etc/os-release && echo ${UBUNTU_CODENAME:-${VERSION_CODENAME}})_all.deb"
-dpkg -i /tmp/ros2-apt-source.deb
-
-# Install development tools and ROS tools
-apt update && apt install -y \
- python3-flake8-docstrings \
- python3-pip \
- python3-pytest-cov \
- ros-dev-tools \
- python3-flake8-blind-except \
- python3-flake8-builtins \
- python3-flake8-class-newline \
- python3-flake8-comprehensions \
- python3-flake8-deprecated \
- python3-flake8-import-order \
- python3-flake8-quotes \
- python3-pytest-repeat \
- python3-pytest-rerunfailures
-
-python3 -m pip install -U colcon-common-extensions vcstool
-
-mkdir -p /ros2_humble/src \
- && cd /ros2_humble \
- && vcs import --input https://raw.githubusercontent.com/ros2/ros2/humble/ros2.repos src
-
-apt update && apt upgrade -y
-
-rosdep init \
- && rosdep update \
- && rosdep install --from-paths src --ignore-src -y --skip-keys="fastcdr rti-connext-dds-6.0.1 urdfdom_headers"
-
-colcon build
-echo "ROS Humble installation completed successfully!"
\ No newline at end of file
diff --git a/docker/sensor_dep_ros1/firmware_comm/CMakeLists.txt b/docker/sensor_dep_ros1/firmware_comm/CMakeLists.txt
deleted file mode 100644
index f8f1c9c..0000000
--- a/docker/sensor_dep_ros1/firmware_comm/CMakeLists.txt
+++ /dev/null
@@ -1,30 +0,0 @@
-cmake_minimum_required(VERSION 2.4.6)
-include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
-
-# Set the build type. Options are:
-# Coverage : w/ debug symbols, w/o optimization, w/ code-coverage
-# Debug : w/ debug symbols, w/o optimization
-# Release : w/o debug symbols, w/ optimization
-# RelWithDebInfo : w/ debug symbols, w/ optimization
-# MinSizeRel : w/o debug symbols, w/ optimization, stripped binaries
-#set(ROS_BUILD_TYPE RelWithDebInfo)
-
-rosbuild_init()
-
-#set the default path for built executables to the "bin" directory
-set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
-#set the default path for built libraries to the "lib" directory
-set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
-
-#uncomment if you have defined messages
-#rosbuild_genmsg()
-#uncomment if you have defined services
-#rosbuild_gensrv()
-
-#common commands for building c++ executables and libraries
-#rosbuild_add_library(${PROJECT_NAME} src/example.cpp)
-#target_link_libraries(${PROJECT_NAME} another_library)
-#rosbuild_add_boost_directories()
-#rosbuild_link_boost(${PROJECT_NAME} thread)
-#rosbuild_add_executable(example examples/example.cpp)
-#target_link_libraries(example ${PROJECT_NAME})
diff --git a/docker/sensor_dep_ros1/firmware_comm/Makefile b/docker/sensor_dep_ros1/firmware_comm/Makefile
deleted file mode 100644
index b75b928..0000000
--- a/docker/sensor_dep_ros1/firmware_comm/Makefile
+++ /dev/null
@@ -1 +0,0 @@
-include $(shell rospack find mk)/cmake.mk
\ No newline at end of file
diff --git a/docker/sensor_dep_ros1/firmware_comm/launch/firmware_comm.launch b/docker/sensor_dep_ros1/firmware_comm/launch/firmware_comm.launch
deleted file mode 100644
index 3dc7378..0000000
--- a/docker/sensor_dep_ros1/firmware_comm/launch/firmware_comm.launch
+++ /dev/null
@@ -1,13 +0,0 @@
-
-
-
-
-
-
- require:
- publishers: [ wheel_pose ]
- subscribers: [ cmd_vel ]
-
-
-
-
\ No newline at end of file
diff --git a/docker/sensor_dep_ros1/firmware_comm/mainpage.dox b/docker/sensor_dep_ros1/firmware_comm/mainpage.dox
deleted file mode 100644
index d69c247..0000000
--- a/docker/sensor_dep_ros1/firmware_comm/mainpage.dox
+++ /dev/null
@@ -1,14 +0,0 @@
-/**
-\mainpage
-\htmlinclude manifest.html
-
-\b firmware_comm
-
-
-
--->
-
-
-*/
diff --git a/docker/sensor_dep_ros1/firmware_comm/manifest.xml b/docker/sensor_dep_ros1/firmware_comm/manifest.xml
deleted file mode 100644
index a8cd6e2..0000000
--- a/docker/sensor_dep_ros1/firmware_comm/manifest.xml
+++ /dev/null
@@ -1,13 +0,0 @@
-
-
-
- firmware_comm
-
-
- root
- BSD
-
- http://ros.org/wiki/firmware_comm
-
-
-
diff --git a/docker/sensor_dep_ros1/rosserial_msgs/CHANGELOG.rst b/docker/sensor_dep_ros1/rosserial_msgs/CHANGELOG.rst
deleted file mode 100644
index ee8c98d..0000000
--- a/docker/sensor_dep_ros1/rosserial_msgs/CHANGELOG.rst
+++ /dev/null
@@ -1,105 +0,0 @@
-^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
-Changelog for package rosserial_msgs
-^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
-
-0.9.2 (2021-04-02)
-------------------
-
-0.9.1 (2020-09-09)
-------------------
-
-0.9.0 (2020-08-25)
-------------------
-* Fix Travis for Noetic + Python 3
-* Bump minimum CMake version to 3.7.2 (Melodic).
-* Drop separate node for message service (`#446 `_)
-* Contributors: Mike Purvis
-
-0.8.0 (2018-10-11)
-------------------
-
-0.7.7 (2017-11-29)
-------------------
-* Fix catkin lint errors (`#296 `_)
-* Contributors: Bei Chen Liu
-
-0.7.6 (2017-03-01)
-------------------
-
-0.7.5 (2016-11-22)
-------------------
-
-0.7.4 (2016-09-21)
-------------------
-
-0.7.3 (2016-08-05)
-------------------
-
-0.7.2 (2016-07-15)
-------------------
-
-0.7.1 (2015-07-06)
-------------------
-
-0.7.0 (2015-04-23)
-------------------
-
-0.6.3 (2014-11-05)
-------------------
-
-0.6.2 (2014-09-10)
-------------------
-
-0.6.1 (2014-06-30)
-------------------
-
-0.6.0 (2014-06-11)
-------------------
-* Uncomment ID_TX_STOP constant, per `#111 `_
-* Contributors: Mike Purvis
-
-0.5.6 (2014-06-11)
-------------------
-* Add Mike Purvis as maintainer to all but xbee.
-* remove ID_TX_STOP from rosserial_msgs/msg/TopicInfo.msg, using hardcode modification. fix the dupilcated registration problem of subscriber
-* modified rosserial
-* Contributors: Mike Purvis, Moju Zhao
-
-0.5.5 (2014-01-14)
-------------------
-
-0.5.4 (2013-10-17)
-------------------
-
-0.5.3 (2013-09-21)
-------------------
-* Add message info service and stub of node to provide it, for
-rosserial_server support.
-
-0.5.2 (2013-07-17)
-------------------
-
-* Fix release version
-
-0.5.1 (2013-07-15)
-------------------
-
-0.4.5 (2013-07-02)
-------------------
-
-0.4.4 (2013-03-20)
-------------------
-
-0.4.3 (2013-03-13 14:08)
-------------------------
-
-0.4.2 (2013-03-13 01:15)
-------------------------
-
-0.4.1 (2013-03-09)
-------------------
-
-0.4.0 (2013-03-08)
-------------------
-* Changed DEBUG log level to ROSDEBUG.
-* initial catkin version on github
diff --git a/docker/sensor_dep_ros1/rosserial_msgs/CMakeLists.txt b/docker/sensor_dep_ros1/rosserial_msgs/CMakeLists.txt
deleted file mode 100644
index c525612..0000000
--- a/docker/sensor_dep_ros1/rosserial_msgs/CMakeLists.txt
+++ /dev/null
@@ -1,21 +0,0 @@
-cmake_minimum_required(VERSION 3.7.2)
-project(rosserial_msgs)
-
-find_package(catkin REQUIRED COMPONENTS
- message_generation
-)
-
-add_message_files(FILES
- Log.msg
- TopicInfo.msg
-)
-
-add_service_files(FILES
- RequestParam.srv
-)
-
-generate_messages()
-
-catkin_package(CATKIN_DEPENDS
- message_runtime
-)
diff --git a/docker/sensor_dep_ros1/rosserial_msgs/msg/Log.msg b/docker/sensor_dep_ros1/rosserial_msgs/msg/Log.msg
deleted file mode 100644
index 7239876..0000000
--- a/docker/sensor_dep_ros1/rosserial_msgs/msg/Log.msg
+++ /dev/null
@@ -1,10 +0,0 @@
-
-#ROS Logging Levels
-uint8 ROSDEBUG=0
-uint8 INFO=1
-uint8 WARN=2
-uint8 ERROR=3
-uint8 FATAL=4
-
-uint8 level
-string msg
diff --git a/docker/sensor_dep_ros1/rosserial_msgs/msg/TopicInfo.msg b/docker/sensor_dep_ros1/rosserial_msgs/msg/TopicInfo.msg
deleted file mode 100644
index dafd6b0..0000000
--- a/docker/sensor_dep_ros1/rosserial_msgs/msg/TopicInfo.msg
+++ /dev/null
@@ -1,21 +0,0 @@
-# special topic_ids
-uint16 ID_PUBLISHER=0
-uint16 ID_SUBSCRIBER=1
-uint16 ID_SERVICE_SERVER=2
-uint16 ID_SERVICE_CLIENT=4
-uint16 ID_PARAMETER_REQUEST=6
-uint16 ID_LOG=7
-uint16 ID_TIME=10
-uint16 ID_TX_STOP=11
-
-# The endpoint ID for this topic
-uint16 topic_id
-
-string topic_name
-string message_type
-
-# MD5 checksum for this message type
-string md5sum
-
-# size of the buffer message must fit in
-int32 buffer_size
diff --git a/docker/sensor_dep_ros1/rosserial_msgs/package.xml b/docker/sensor_dep_ros1/rosserial_msgs/package.xml
deleted file mode 100644
index 9f8ac6d..0000000
--- a/docker/sensor_dep_ros1/rosserial_msgs/package.xml
+++ /dev/null
@@ -1,18 +0,0 @@
-
- rosserial_msgs
- 0.9.2
-
- Messages for automatic topic configuration using rosserial.
-
- Michael Ferguson
- Paul Bouchier
- Mike Purvis
- BSD
- http://ros.org/wiki/rosserial_msgs
-
- catkin
-
- message_generation
-
- message_runtime
-
diff --git a/docker/sensor_dep_ros1/rosserial_msgs/srv/RequestParam.srv b/docker/sensor_dep_ros1/rosserial_msgs/srv/RequestParam.srv
deleted file mode 100644
index ca605e8..0000000
--- a/docker/sensor_dep_ros1/rosserial_msgs/srv/RequestParam.srv
+++ /dev/null
@@ -1,7 +0,0 @@
-string name
-
----
-
-int32[] ints
-float32[] floats
-string[] strings
diff --git a/docker/sensor_dep_ros1/rosserial_server/CHANGELOG.rst b/docker/sensor_dep_ros1/rosserial_server/CHANGELOG.rst
deleted file mode 100644
index e8d8efd..0000000
--- a/docker/sensor_dep_ros1/rosserial_server/CHANGELOG.rst
+++ /dev/null
@@ -1,130 +0,0 @@
-^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
-Changelog for package rosserial_server
-^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
-
-0.9.2 (2021-04-02)
-------------------
-* Add python3-dev as build depend (`#544 `_)
-* Contributors: Tobias Fischer
-
-0.9.1 (2020-09-09)
-------------------
-* Add boost::thread dependency to rosserial_server (`#513 `_)
-* Contributors: Mike Purvis
-
-0.9.0 (2020-08-25)
-------------------
-* Only initialize embedded python interpreter once. (`#491 `_)
-* Port 482 and 483 forward from Melodic branch (`#492 `_)
-* Fix warning when using std_msgs/Empty (`#482 `_)
-* Bump minimum CMake version to 3.7.2 (Melodic).
-* Removed unused service client for message info service (`#481 `_)
-* Call io_service.stop() when ros::ok() returns false (`#477 `_)
-* Call Py_Finalize before throwing exception (`#476 `_)
-* [Windows] use c++ signed trait to replace ssize_t for better portability. (`#463 `_)
-* Port rosserial_server to Boost 1.71. (`#468 `_)
-* rosserial_server: update install rules for binary targets (`#457 `_)
-* Fix bug: assign the md5 for service (`#449 `_)
-* Contributors: Hermann von Kleist, Johannes Meyer, Mike Purvis, Sean Yen, è¶™ã€€æ¼ å±…(Zhao, Moju)
-
-0.8.0 (2018-10-11)
-------------------
-* Fix compiling on boost > 1.66 (`#362 `_)
- Reflective of changes made to boost::asio noted here:
- http://www.boost.org/doc/libs/1_66_0/doc/html/boost_asio/net_ts.html
-* Contributors: Fan Jiang
-
-0.7.7 (2017-11-29)
-------------------
-* Fix catkin lint errors (`#296 `_)
-* Contributors: Bei Chen Liu
-
-0.7.6 (2017-03-01)
-------------------
-
-0.7.5 (2016-11-22)
-------------------
-* Fixing build errors for boost >=1.60 (`#226 `_) (`#250 `_)
-* Contributors: Malte Splietker
-
-0.7.4 (2016-09-21)
-------------------
-* Use catkin_EXPORTED_TARGETS to avoid CMake warning (`#246 `_)
-* Fix AsyncReadBuffer for UDP socket case. (`#245 `_)
-* Contributors: Mike Purvis
-
-0.7.3 (2016-08-05)
-------------------
-* Avoid runaway async condition when port is bad. (`#236 `_)
-* Add missing install rule for udp_socket_node
-* Make the ~require param configurable from Session. (`#233 `_)
-* Contributors: Mike Purvis
-
-0.7.2 (2016-07-15)
-------------------
-* Implementation of native UDP rosserial server. (`#231 `_)
-* Explicit session lifecycle for the serial server. (`#228 `_)
- This is a long overdue change which will resolve some crashes when
- USB serial devices return error states in the face of noise or other
- interruptions.
-* Support for VER1 protocol has been dropped.
-* Handle log messages in rosserial_server
-* Contributors: Mike Purvis, mkrauter
-
-0.7.1 (2015-07-06)
-------------------
-
-0.7.0 (2015-04-23)
-------------------
-* Fill out description field in package.xml.
-* Bugfix for checksum.
- Publishing topics fails when messages are over 256 bytes in length due to checksum() function or'ing high and low byte instead of adding them.
-* rosserial_server: Properly receive messages > 255 bytes.
-* Contributors: Chad Attermann, Mike Purvis
-
-0.6.3 (2014-11-05)
-------------------
-* Add more log output, don't end the session for certain write errors.
-* Contributors: Mike Purvis
-
-0.6.2 (2014-09-10)
-------------------
-* Bugfix for interrupted sessions.
- This is a two-part fix for an issue causes a segfault when the device
- disappears during operation, for example a ttyACM device which is unplugged.
- The AsyncReadBuffer part avoids calling a callback after the object
- owning it has destructed, and the SerialSession part avoids recreating
- itself until the previous instance has finished the destructor and been
- full destroyed.
-* Add dependency on rosserial_msgs_gencpp, fixes `#133 `_
-* Make ServiceClient::handle public, to fix compilation bug on some platforms.
-* Enabled registration of service clients
-* Add namespaces to headers, swap ROS thread to foreground.
-* Move headers to include path, rename to follow ROS style.
-
-0.6.1 (2014-06-30)
-------------------
-
-0.6.0 (2014-06-11)
-------------------
-
-0.5.6 (2014-06-11)
-------------------
-* Fixed build error due to variable being read as a function due to missing parenthesis
-* Add rosserial_python as dependency of rosserial_server
-* Contributors: Mike Purvis, spaghetti-
-
-0.5.5 (2014-01-14)
-------------------
-* Add support for require/publishers and require/subscribers parameters.
-* Use stream logging in rosserial_server
-
-0.5.4 (2013-10-17)
-------------------
-
-0.5.3 (2013-09-21)
-------------------
-* New package: rosserial_server
-* Contains example launch file for serial configuration of server
-* Working now with both Groovy and Hydro clients.
-* Subscriber to correctly declare known md5 and topic type from client.
diff --git a/docker/sensor_dep_ros1/rosserial_server/CMakeLists.txt b/docker/sensor_dep_ros1/rosserial_server/CMakeLists.txt
deleted file mode 100644
index 6e57211..0000000
--- a/docker/sensor_dep_ros1/rosserial_server/CMakeLists.txt
+++ /dev/null
@@ -1,77 +0,0 @@
-cmake_minimum_required(VERSION 3.7.2)
-project(rosserial_server)
-
-find_package(catkin REQUIRED COMPONENTS
- roscpp
- rosserial_msgs
- std_msgs
- topic_tools
-)
-
-find_package(Boost REQUIRED COMPONENTS
- system
- thread
-)
-
-find_package(PythonLibs REQUIRED)
-
-catkin_package(
- INCLUDE_DIRS include
- CATKIN_DEPENDS
- roscpp
- rosserial_msgs
- std_msgs
- topic_tools
- LIBRARIES ${PROJECT_NAME}_lookup
-)
-
-include_directories(
- include
- ${Boost_INCLUDE_DIRS}
- ${catkin_INCLUDE_DIRS}
-)
-
-add_library(${PROJECT_NAME}_lookup src/msg_lookup.cpp)
-target_link_libraries(${PROJECT_NAME}_lookup ${PYTHON_LIBRARY})
-target_include_directories(${PROJECT_NAME}_lookup SYSTEM PRIVATE ${PYTHON_INCLUDE_DIR})
-
-add_executable(${PROJECT_NAME}_serial_node src/serial_node.cpp)
-target_link_libraries(${PROJECT_NAME}_serial_node ${catkin_LIBRARIES} ${PROJECT_NAME}_lookup)
-set_target_properties(${PROJECT_NAME}_serial_node PROPERTIES OUTPUT_NAME serial_node PREFIX "")
-add_dependencies(${PROJECT_NAME}_serial_node ${catkin_EXPORTED_TARGETS})
-
-add_executable(${PROJECT_NAME}_socket_node src/socket_node.cpp)
-target_link_libraries(${PROJECT_NAME}_socket_node ${catkin_LIBRARIES} ${PROJECT_NAME}_lookup)
-set_target_properties(${PROJECT_NAME}_socket_node PROPERTIES OUTPUT_NAME socket_node PREFIX "")
-add_dependencies(${PROJECT_NAME}_socket_node ${catkin_EXPORTED_TARGETS})
-
-add_executable(${PROJECT_NAME}_udp_socket_node src/udp_socket_node.cpp)
-target_link_libraries(${PROJECT_NAME}_udp_socket_node ${catkin_LIBRARIES} ${PROJECT_NAME}_lookup)
-set_target_properties(${PROJECT_NAME}_udp_socket_node PROPERTIES OUTPUT_NAME udp_socket_node PREFIX "")
-add_dependencies(${PROJECT_NAME}_udp_socket_node ${catkin_EXPORTED_TARGETS})
-
-install(
- TARGETS
- ${PROJECT_NAME}_lookup
- ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
- LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
- RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
-)
-
-install(
- TARGETS
- ${PROJECT_NAME}_serial_node
- ${PROJECT_NAME}_socket_node
- ${PROJECT_NAME}_udp_socket_node
- RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
-)
-
-install(
- DIRECTORY launch
- DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
-)
-
-install(
- DIRECTORY include/${PROJECT_NAME}/
- DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
-)
diff --git a/docker/sensor_dep_ros1/rosserial_server/include/rosserial_server/async_read_buffer.h b/docker/sensor_dep_ros1/rosserial_server/include/rosserial_server/async_read_buffer.h
deleted file mode 100644
index 586fcae..0000000
--- a/docker/sensor_dep_ros1/rosserial_server/include/rosserial_server/async_read_buffer.h
+++ /dev/null
@@ -1,204 +0,0 @@
-/**
- *
- * \file
- * \brief Helper object for successive reads from a ReadStream.
- * \author Mike Purvis
- * \copyright Copyright (c) 2013, Clearpath Robotics, Inc.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution.
- * * Neither the name of Clearpath Robotics, Inc. nor the
- * names of its contributors may be used to endorse or promote products
- * derived from this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
- * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
- * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
- * DISCLAIMED. IN NO EVENT SHALL CLEARPATH ROBOTICS, INC. BE LIABLE FOR ANY
- * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
- * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
- * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
- * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
- * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
- *
- * Please send comments, questions, or patches to code@clearpathrobotics.com
- *
- */
-
-#ifndef ROSSERIAL_SERVER_ASYNC_READ_BUFFER_H
-#define ROSSERIAL_SERVER_ASYNC_READ_BUFFER_H
-
-#include
-#include
-#include
-
-#include
-
-// ssize_t is POSIX-only type. Use make_signed for portable code.
-#include // size_t
-#include // std::make_signed
-typedef std::make_signed::type signed_size_t;
-
-namespace rosserial_server
-{
-
-template
-class AsyncReadBuffer
-{
-public:
- AsyncReadBuffer(AsyncReadStream& s, size_t capacity,
- boost::function error_callback)
- : stream_(s), read_requested_bytes_(0), error_callback_(error_callback) {
- reset();
- mem_.resize(capacity);
- ROS_ASSERT_MSG(error_callback_, "Bad error callback passed to read buffer.");
- }
-
- /**
- * @brief Commands a fixed number of bytes from the buffer. This may be fulfilled from existing
- * buffer content, or following a hardware read if required.
- */
- void read(size_t requested_bytes, boost::function callback) {
- ROS_DEBUG_STREAM_NAMED("async_read", "Buffer read of " << requested_bytes << " bytes, " <<
- "wi: " << write_index_ << ", ri: " << read_index_);
-
- ROS_ASSERT_MSG(read_requested_bytes_ == 0, "Bytes requested is nonzero, is there an operation already pending?");
- ROS_ASSERT_MSG(callback, "Bad read success callback function.");
- read_success_callback_ = callback;
- read_requested_bytes_ = requested_bytes;
-
- if (read_requested_bytes_ > mem_.size())
- {
- // Insufficient room in the buffer for the requested bytes,
- ROS_ERROR_STREAM_NAMED("async_read", "Requested to read " << read_requested_bytes_ <<
- " bytes, but buffer capacity is only " << mem_.size() << ".");
- error_callback_(boost::system::errc::make_error_code(boost::system::errc::no_buffer_space));
- return;
- }
-
- // Number of bytes which must be transferred to satisfy the request.
- signed_size_t transfer_bytes = read_requested_bytes_ - bytesAvailable();
-
- if (transfer_bytes > 0)
- {
- // If we don't have enough headroom in the buffer, we'll have to shift what's currently in there to make room.
- if (bytesHeadroom() < transfer_bytes)
- {
- memmove(&mem_[0], &mem_[read_index_], bytesAvailable());
- write_index_ = bytesAvailable();
- read_index_ = 0;
- }
-
- // Initiate a read from hardware so that we have enough bytes to fill the user request.
- ROS_DEBUG_STREAM_NAMED("async_read", "Requesting transfer of at least " << transfer_bytes << " byte(s).");
- boost::asio::async_read(stream_,
- boost::asio::buffer(&mem_[write_index_], bytesHeadroom()),
- boost::asio::transfer_at_least(transfer_bytes),
- boost::bind(&AsyncReadBuffer::callback, this,
- boost::asio::placeholders::error,
- boost::asio::placeholders::bytes_transferred));
- }
- else
- {
- // We have enough in the buffer already, can fill the request without going to hardware.
- callSuccessCallback();
- }
- }
-
-private:
- void reset()
- {
- read_index_ = 0;
- write_index_ = 0;
- }
-
- inline size_t bytesAvailable()
- {
- return write_index_ - read_index_;
- }
-
- inline size_t bytesHeadroom()
- {
- return mem_.size() - write_index_;
- }
-
- /**
- * @brief The internal callback which is called by the boost::asio::async_read invocation
- * in the public read method above.
- */
- void callback(const boost::system::error_code& error, size_t bytes_transferred)
- {
- if (error)
- {
- read_requested_bytes_ = 0;
- read_success_callback_.clear();
- ROS_DEBUG_STREAM_NAMED("async_read", "Read operation failed with: " << error);
-
- if (error == boost::asio::error::operation_aborted)
- {
- // Special case for operation_aborted. The abort callback comes when the owning Session
- // is in the middle of teardown, which means the callback is no longer valid.
- }
- else
- {
- error_callback_(error);
- }
- return;
- }
-
- write_index_ += bytes_transferred;
- ROS_DEBUG_STREAM_NAMED("async_read", "Successfully read " << bytes_transferred << " byte(s), now " << bytesAvailable() << " available.");
- callSuccessCallback();
- }
-
- /**
- * @brief Calls the user's callback. This is a separate function because it gets called from two
- * places, depending whether or not an actual HW read is required to fill the request.
- */
- void callSuccessCallback()
- {
- ROS_DEBUG_STREAM_NAMED("async_read", "Invoking success callback with buffer of requested size " <<
- read_requested_bytes_ << " byte(s).");
-
- ros::serialization::IStream stream(&mem_[read_index_], read_requested_bytes_);
- read_index_ += read_requested_bytes_;
-
- // Post the callback rather than executing it here so, so that we have a chance to do the cleanup
- // below prior to it actually getting run, in the event that the callback queues up another read.
-#if BOOST_VERSION >= 107000
- boost::asio::post(stream_.get_executor(), boost::bind(read_success_callback_, stream));
-#else
- stream_.get_io_service().post(boost::bind(read_success_callback_, stream));
-#endif
-
- // Resetting these values clears our state so that we know there isn't a callback pending.
- read_requested_bytes_ = 0;
- read_success_callback_.clear();
-
- if (bytesAvailable() == 0)
- {
- ROS_DEBUG_STREAM_NAMED("async_read", "Buffer is empty, resetting indexes to the beginning.");
- reset();
- }
- }
-
- AsyncReadStream& stream_;
- std::vector mem_;
-
- size_t write_index_;
- size_t read_index_;
- boost::function error_callback_;
-
- boost::function read_success_callback_;
- size_t read_requested_bytes_;
-};
-
-} // namespace
-
-#endif // ROSSERIAL_SERVER_ASYNC_READ_BUFFER_H
diff --git a/docker/sensor_dep_ros1/rosserial_server/include/rosserial_server/msg_lookup.h b/docker/sensor_dep_ros1/rosserial_server/include/rosserial_server/msg_lookup.h
deleted file mode 100644
index 28e60b9..0000000
--- a/docker/sensor_dep_ros1/rosserial_server/include/rosserial_server/msg_lookup.h
+++ /dev/null
@@ -1,44 +0,0 @@
-/**
- * \author Mike Purvis
- * \copyright Copyright (c) 2019, Clearpath Robotics, Inc.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution.
- * * Neither the name of Clearpath Robotics, Inc. nor the
- * names of its contributors may be used to endorse or promote products
- * derived from this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
- * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
- * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
- * DISCLAIMED. IN NO EVENT SHALL CLEARPATH ROBOTICS, INC. BE LIABLE FOR ANY
- * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
- * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
- * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
- * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
- * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
- *
- * Please send comments, questions, or patches to code@clearpathrobotics.com
- */
-
-#include
-#include
-
-namespace rosserial_server
-{
-
-struct MsgInfo
-{
- std::string md5sum;
- std::string full_text;
-};
-
-const MsgInfo lookupMessage(const std::string& message_type, const std::string submodule = "msg");
-
-} // namespace rosserial_server
diff --git a/docker/sensor_dep_ros1/rosserial_server/include/rosserial_server/serial_session.h b/docker/sensor_dep_ros1/rosserial_server/include/rosserial_server/serial_session.h
deleted file mode 100644
index 2a0bc15..0000000
--- a/docker/sensor_dep_ros1/rosserial_server/include/rosserial_server/serial_session.h
+++ /dev/null
@@ -1,118 +0,0 @@
-/**
- *
- * \file
- * \brief Single, reconnecting class for a serial rosserial session.
- * \author Mike Purvis
- * \copyright Copyright (c) 2013, Clearpath Robotics, Inc.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution.
- * * Neither the name of Clearpath Robotics, Inc. nor the
- * names of its contributors may be used to endorse or promote products
- * derived from this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
- * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
- * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
- * DISCLAIMED. IN NO EVENT SHALL CLEARPATH ROBOTICS, INC. BE LIABLE FOR ANY
- * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
- * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
- * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
- * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
- * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
- *
- * Please send comments, questions, or patches to code@clearpathrobotics.com
- *
- */
-
-#ifndef ROSSERIAL_SERVER_SERIAL_SESSION_H
-#define ROSSERIAL_SERVER_SERIAL_SESSION_H
-
-#include
-#include
-#include
-
-#include
-
-#include "rosserial_server/session.h"
-
-namespace rosserial_server
-{
-
-class SerialSession : public Session
-{
-public:
- SerialSession(boost::asio::io_service& io_service, std::string port, int baud)
- : Session(io_service), port_(port), baud_(baud), timer_(io_service)
- {
- ROS_INFO_STREAM("rosserial_server session configured for " << port_ << " at " << baud << "bps.");
-
- failed_connection_attempts_ = 0;
- check_connection();
- }
-
-private:
- void check_connection()
- {
- if (!is_active())
- {
- attempt_connection();
- }
-
- // Every second, check again if the connection should be reinitialized,
- // if the ROS node is still up.
- if (ros::ok())
- {
- timer_.expires_from_now(boost::posix_time::milliseconds(2000));
- timer_.async_wait(boost::bind(&SerialSession::check_connection, this));
- }
- else
- {
- shutdown();
- }
- }
-
- void attempt_connection()
- {
- ROS_DEBUG("Opening serial port.");
-
- boost::system::error_code ec;
- socket().open(port_, ec);
- if (ec) {
- failed_connection_attempts_++;
- if (failed_connection_attempts_ == 1) {
- ROS_ERROR_STREAM("Unable to open port " << port_ << ": " << ec);
- } else {
- ROS_DEBUG_STREAM("Unable to open port " << port_ << " (" << failed_connection_attempts_ << "): " << ec);
- }
- return;
- }
- ROS_INFO_STREAM("Opened " << port_);
- failed_connection_attempts_ = 0;
-
- typedef boost::asio::serial_port_base serial;
- socket().set_option(serial::baud_rate(baud_));
- socket().set_option(serial::character_size(8));
- socket().set_option(serial::stop_bits(serial::stop_bits::one));
- socket().set_option(serial::parity(serial::parity::none));
- socket().set_option(serial::flow_control(serial::flow_control::none));
-
- // Kick off the session.
- start();
- }
-
- std::string port_;
- int baud_;
- boost::asio::deadline_timer timer_;
- int failed_connection_attempts_;
-};
-
-} // namespace
-
-#endif // ROSSERIAL_SERVER_SERIAL_SESSION_H
diff --git a/docker/sensor_dep_ros1/rosserial_server/include/rosserial_server/session.h b/docker/sensor_dep_ros1/rosserial_server/include/rosserial_server/session.h
deleted file mode 100644
index e7f8ab7..0000000
--- a/docker/sensor_dep_ros1/rosserial_server/include/rosserial_server/session.h
+++ /dev/null
@@ -1,625 +0,0 @@
-/**
- *
- * \file
- * \brief Class representing a session between this node and a
- * templated rosserial client.
- * \author Mike Purvis
- * \copyright Copyright (c) 2013, Clearpath Robotics, Inc.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution.
- * * Neither the name of Clearpath Robotics, Inc. nor the
- * names of its contributors may be used to endorse or promote products
- * derived from this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
- * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
- * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
- * DISCLAIMED. IN NO EVENT SHALL CLEARPATH ROBOTICS, INC. BE LIABLE FOR ANY
- * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
- * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
- * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
- * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
- * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
- *
- * Please send comments, questions, or patches to code@clearpathrobotics.com
- *
- */
-
-#ifndef ROSSERIAL_SERVER_SESSION_H
-#define ROSSERIAL_SERVER_SESSION_H
-
-#include