Skip to content
New issue

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

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

Already on GitHub? Sign in to your account

Odometry readjustement #31

Merged
merged 69 commits into from
Feb 26, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
69 commits
Select commit Hold shift + click to select a range
99150c8
add service adjust_odometry
PhileasL Feb 1, 2021
d152d24
add service caller adjust odometry + update tf map->odom on readjust
PhileasL Feb 1, 2021
34ceda0
rework on robot_param controller and adding inflation layer costmap
PhileasL Feb 2, 2021
efa6e54
storing 20 tf + retrieve the tf near the stamp of the tf in callback
PhileasL Feb 2, 2021
2b933cc
simulation get_sim_time + true quaternion from sim
PhileasL Feb 3, 2021
417dbab
condition change + managing extreme indexes
PhileasL Feb 3, 2021
c329478
extract_pose_from_transform + set_transform_from_pose functions
PhileasL Feb 3, 2021
baff0c6
algorithm to get base_link_relative_to_new_odom tf
PhileasL Feb 3, 2021
7129137
sending new tf and new odom with readjustement
PhileasL Feb 3, 2021
b4eddf0
Init _previous_tf vector + adding dependency to cmakelist
PhileasL Feb 3, 2021
2367bf5
TransformBroadcaster + 'adjust_odometry' publisher + quaternion_to_euler
PhileasL Feb 3, 2021
d7ba7a7
Changing odometry_readjustement strategy, removing service
PhileasL Feb 4, 2021
6bb8e49
Re-basculing to static map to odom transform
PhileasL Feb 4, 2021
d40ed7c
Getting the static map to odom transform
PhileasL Feb 4, 2021
2af55ca
use sim time + clean all traces of service 'ajust_odometry'
PhileasL Feb 4, 2021
925dfb1
The key is to update variables instead of tf !
PhileasL Feb 4, 2021
8a6166d
strange behavior of tf2::doTransform, need my own functions
PhileasL Feb 4, 2021
7e4ccd9
It might be all the functions i need
PhileasL Feb 4, 2021
3e0476c
setting up the idea, need to fill the functions now
PhileasL Feb 4, 2021
fc3a017
almost working, adding a dummy function to avoid odom sliding
PhileasL Feb 4, 2021
92b1899
Little tweaking on tf, working good now !
PhileasL Feb 4, 2021
f16543b
A static transformation need to be publish only once + little fixes
PhileasL Feb 4, 2021
d96d9a8
Publishing the robot transformation for drive to readjust odometry
PhileasL Feb 4, 2021
abe9844
small fix, can now recalibrate even if the information is .75s from past
PhileasL Feb 5, 2021
1e9f406
teb_local_planner no longer turn 2*180° for a simple backward drive
PhileasL Feb 5, 2021
d5c14eb
Remove things that needed to be delete in merge of PR #27 #28
PhileasL Feb 8, 2021
7ef6151
Global planner works now at 2Hz, drive's garbage log not showing anymore
PhileasL Feb 8, 2021
d17a549
Local_costmap contains obstacles for teb_local_planner
PhileasL Feb 8, 2021
88833b5
Tweak of the global_costmap for an acceptable global_planning
PhileasL Feb 8, 2021
c472520
Teb_local_planner tweak:
PhileasL Feb 8, 2021
9b4ab36
Hello teb_obstacles node !
PhileasL Feb 8, 2021
9994d67
teb_obstales node launching with nav
PhileasL Feb 8, 2021
7a9e9e5
Subscribing + callback to allies and ennemies topics
PhileasL Feb 9, 2021
58e6888
Initialisation of obstacles array
PhileasL Feb 9, 2021
7c8dd54
dictionnary_index_id:
PhileasL Feb 9, 2021
ef09df5
ennemies_subscription_callback function of teb_obstacles
PhileasL Feb 9, 2021
421869c
WIP on allies_subscription_callback for teb_obstacles
PhileasL Feb 9, 2021
6f63d31
Set_obstacles function for teb_obstacles
PhileasL Feb 9, 2021
3528e58
Publishing dynamic obstacles each .5s + including them in teb config
PhileasL Feb 9, 2021
691dfe9
/robot/get_odom_map_tf service that returns the initial map->odom tf
PhileasL Feb 10, 2021
b230aba
Client of /robot/get_odom_map_tf for future pose transform
PhileasL Feb 10, 2021
803b68d
Different allie tracking strategy for dynamic obstacle
PhileasL Feb 10, 2021
df97f05
removing useless remapping + commentaries on teb_obstacles functions
PhileasL Feb 10, 2021
422108a
Robot position extrapolation:
PhileasL Feb 18, 2021
d619826
Repositionning of vlx in webots + asterix supervisor: TRUE
PhileasL Feb 19, 2021
bcc1be7
Gobelets removing
PhileasL Feb 19, 2021
0855252
Min x and y from the walls for a full turn without collisions
PhileasL Feb 19, 2021
c984fed
Tweak of the laser response noise + sleep time between samples
PhileasL Feb 19, 2021
5d7a74f
vlx_array + function to get all distances
PhileasL Feb 20, 2021
59cd70a
full path and distance getting for sector 1
PhileasL Feb 20, 2021
c2c2e66
csv ready
PhileasL Feb 21, 2021
55b91e1
acquire_data function
PhileasL Feb 21, 2021
0b725de
obstacle avoidance
PhileasL Feb 21, 2021
a06597f
vlx + remove_gobelets functions
PhileasL Feb 21, 2021
4019c1c
reading csv
PhileasL Feb 21, 2021
63cf1d2
regression test using NuSVR from sklearn
PhileasL Feb 21, 2021
bda036d
testing model function
PhileasL Feb 21, 2021
063cee7
Testing a new splitting strategy
PhileasL Feb 22, 2021
8a94cb9
Testing the new strategy
PhileasL Feb 22, 2021
3bac8c8
Data from machine learning before deleting the unused method
PhileasL Feb 25, 2021
ac909ce
Removing unused method
PhileasL Feb 25, 2021
6be5c65
Merge branch 'master' into odometry_readjustement
PhileasL Feb 25, 2021
d99f780
Merge branch 'master' into odometry_readjustement
3wnbr1 Feb 25, 2021
1d66fe3
Blacked python code
PhileasL Feb 26, 2021
be35ecb
Blacked localisation_node + fix lexical problems
PhileasL Feb 26, 2021
1b50224
Refactoring enemies_subscription_callback function
PhileasL Feb 26, 2021
c9739f9
Revert drive log: output="screen"
PhileasL Feb 26, 2021
ded9c98
Alright then, teb_obstacle is trully blacked now
PhileasL Feb 26, 2021
5456500
Removing useless instructions
PhileasL Feb 26, 2021
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,6 @@ Assurancetourix::Assurancetourix() : Node("assurancetourix") {

timer_ = this->create_wall_timer(std::chrono::milliseconds(1000 / refresh_frequency), std::bind(&Assurancetourix::simulation_marker_callback, this));
#endif
//timer_ = this->create_wall_timer(0.3s, std::bind(&Assurancetourix::detect, this)); // to remove for PR
RCLCPP_INFO(this->get_logger(), "Assurancetourix has been started");
}

Expand Down
13 changes: 12 additions & 1 deletion src/modules/localisation/localisation/localisation_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
from rcl_interfaces.msg import SetParametersResult
from visualization_msgs.msg import MarkerArray
from tf2_ros import StaticTransformBroadcaster
from transformix_msgs.srv import TransformixParametersTransformStamped


class Localisation(rclpy.node.Node):
Expand All @@ -28,13 +29,17 @@ def __init__(self):
self._tf.header.frame_id = "map"
self._tf.child_frame_id = "odom"
self.update_transform()
self.get_initial_tf_srv = self.create_service(
TransformixParametersTransformStamped,
"get_odom_map_tf",
self.get_initial_tf_srv_callback,
)
self.subscription_ = self.create_subscription(
MarkerArray,
"/allies_positions_markers",
self.allies_subscription_callback,
10,
)
self.subscription_ # prevent unused variable warning
self.tf_publisher_ = self.create_publisher(
TransformStamped, "adjust_odometry", 10
)
Expand Down Expand Up @@ -114,6 +119,7 @@ def update_transform(self):
self._tf.transform.rotation.y = float(qy)
self._tf.transform.rotation.z = float(qz)
self._tf.transform.rotation.w = float(qw)
self._initial_tf = self._tf
self._tf_brodcaster.sendTransform(self._tf)

def allies_subscription_callback(self, msg):
Expand All @@ -136,6 +142,11 @@ def allies_subscription_callback(self, msg):
self.tf_publisher_.publish(self._tf)
self.last_odom_update = self.get_clock().now().to_msg().sec

def get_initial_tf_srv_callback(self, request, response):
self.get_logger().info(f"incoming request for {self.robot} odom -> map tf")
response.transform_stamped = self._initial_tf
return response


def main(args=None):
"""Entrypoint."""
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
<root main_tree_to_execute="MainTree">
<BehaviorTree ID="MainTree">
<PipelineSequence name="NavigateWithReplanning">
<RateController hz="1.0">
<RateController hz="2.0">
<ComputePathToPose goal="{goal}" path="{path}" planner_id="GridBased"/>
</RateController>
<FollowPath path="{path}" controller_id="DynamicFollowPath"/>
Expand Down
62 changes: 46 additions & 16 deletions src/modules/robot/param/robot.in.yml
Original file line number Diff line number Diff line change
Expand Up @@ -56,33 +56,41 @@ cetautomatix:
controller_server:
ros__parameters:
use_sim_time: !Var use_sim_time
controller_frequency: 40.0
controller_frequency: 20.0
min_x_velocity_threshold: 0.001
min_y_velocity_threshold: 0.5
min_y_velocity_threshold: 0.001
min_theta_velocity_threshold: 0.001
progress_checker_plugin: "progress_checker"
goal_checker_plugin: "goal_checker"
controller_plugins: ["DynamicFollowPath"]
progress_checker:
plugin: "nav2_controller::SimpleProgressChecker"
required_movement_radius: 0.5
required_movement_radius: 0.005
movement_time_allowance: 10.0
goal_checker:
plugin: "nav2_controller::SimpleGoalChecker"
xy_goal_tolerance: 0.02
yaw_goal_tolerance: 0.02
xy_goal_tolerance: 0.01
yaw_goal_tolerance: 0.01
stateful: True
DynamicFollowPath:
plugin: "teb_local_planner::TebLocalPlannerROS"
# Robot footprint
footprint_model.type: polygon

# Goal tolerance
xy_goal_tolerance: 0.01
yaw_goal_tolerance: 0.01

# Obstacles
min_obstacle_dist: 0.01
inflation_dist: 0.1
min_obstacle_dist: 0.03
inflation_dist: 0.25
costmap_converter_plugin: costmap_converter::CostmapToPolygonsDBSMCCH
costmap_converter_spin_thread: True
costmap_converter_rate: 5
include_costmap_obstacles: true
costmap_obstacles_behind_robot_dist: 3.0
include_dynamic_obstacles: true


# Homotopy Class Planner
enable_homotopy_class_planning: True
Expand All @@ -103,6 +111,9 @@ controller_server:
global_plan_overwrite_orientation: true
allow_init_with_backwards_motion: true

# Miscellaneous
map_frame: "map"


controller_server_rclcpp_node:
ros__parameters:
Expand All @@ -112,12 +123,13 @@ controller_server_rclcpp_node:
global_costmap:
global_costmap:
ros__parameters:
lethal_cost_threshold: 253
update_frequency: 5.0
publish_frequency: 5.0
global_frame: map
robot_base_frame: base_link
use_sim_time: !Var use_sim_time
resolution: 0.02
resolution: 0.01
plugins: ["static_layer", "gradient_layer", "inflation_layer"]
static_layer: #subscribe to map
plugin: "nav2_costmap_2d::StaticLayer"
Expand All @@ -131,24 +143,42 @@ global_costmap:
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
enabled: true
inflation_radius: 0.2
cost_scaling_factor: 5.0
inflation_radius: 0.3
cost_scaling_factor: 10.0
inflate_unknown: false
inflate_around_unknown: false
always_send_full_costmap: true

local_costmap: #just enough parameters to disable it
local_costmap:
local_costmap:
ros__parameters:
update_frequency: 0.1
publish_frequency: 0.1
lethal_cost_threshold: 253
trinary_costmap: false
update_frequency: 5.0
publish_frequency: 5.0
global_frame: map
robot_base_frame: base_link
use_sim_time: false
rolling_window: true
width: 6
height: 6
rolling_window: false
resolution: 1.0
static_map: true
plugins: ["static_layer", "gradient_layer", "inflation_layer"]
static_layer:
plugin: nav2_costmap_2d::StaticLayer
gradient_layer: #draw radians circle around ennemies
plugin: "gradient_costmap_layer_plugin/GradientLayer"
enabled: false
gradient_size: 7
gradient_factor: 100
markers_topic: /ennemies_positions_markers
inflation_layer:
plugin: nav2_costmap_2d::InflationLayer
enabled: false
inflation_radius: 0.01
cost_scaling_factor: 5.0
inflate_unknown: false
inflate_around_unknown: false
3wnbr1 marked this conversation as resolved.
Show resolved Hide resolved
always_send_full_costmap: true

map_server:
ros__parameters:
Expand Down
6 changes: 6 additions & 0 deletions src/modules/robot/robot/launcher.py
Original file line number Diff line number Diff line change
Expand Up @@ -126,6 +126,12 @@ def generate_robot_launch_description(robot_namespace: str, simulation=False):
parameters=[params.name],
remappings=remappings,
),
Node(
package="teb_obstacles",
executable="teb_obstacles",
output="screen",
parameters=[],
),
IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[nav2_launch_file_dir, "/navigation_launch.py"]
Expand Down
15 changes: 15 additions & 0 deletions src/navigation/teb_obstacles/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>teb_obstacles</name>
<version>0.8.3</version>
<description>teb_obstacles node compute and send dynamic teb_obstacles</description>
<maintainer email="phileas.lambert@gmail.com">Philéas LAMBERT</maintainer>
<license>ECAM Makers :: CDFR 2021</license>

<exec_depend>rclpy</exec_depend>

<export>
<build_type>ament_python</build_type>
</export>
</package>
Empty file.
4 changes: 4 additions & 0 deletions src/navigation/teb_obstacles/setup.cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
[develop]
script-dir=$base/lib/teb_obstacles
[install]
install-scripts=$base/lib/teb_obstacles
31 changes: 31 additions & 0 deletions src/navigation/teb_obstacles/setup.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
#!/usr/bin/env python3


"""Teb_obstacles package."""


from os import path
from setuptools import setup, find_packages

package_name = "teb_obstacles"

setup(
name=package_name,
version="0.8.3",
packages=find_packages(),
data_files=[
(path.join("share", package_name), ["package.xml"]),
("share/ament_index/resource_index/packages", ["resource/" + package_name]),
],
install_requires=["setuptools"],
zip_safe=True,
author="Philéas LAMBERT",
maintainer="Phileas LAMBERT",
maintainer_email="phileas.lambert@gmail.com",
keywords=["ROS2", "teb_obstacles", "CDFR"],
description="teb_obstacles node compute and send dynamic teb_obstacles",
license="ECAM Makers :: CDFR 2021",
entry_points={
"console_scripts": ["teb_obstacles = teb_obstacles.teb_obstacles:main"],
},
)
Empty file.
Loading