Skip to content

Commit

Permalink
feat: trajectory follower package (autowarefoundation#84)
Browse files Browse the repository at this point in the history
* Back port .auto control packages (autowarefoundation#571)

* Implement Lateral and Longitudinal Control Muxer

* [autowarefoundation#570] Porting wf_simulator

* [autowarefoundation#1189] Deactivate flaky test in 'trajectory_follower_nodes'

* [autowarefoundation#1189] Fix flacky test in 'trajectory_follower_nodes/latlon_muxer'

* [autowarefoundation#1057] Add osqp_interface package

* [autowarefoundation#1057] Add library code for MPC-based lateral control

* [autowarefoundation#1271] Use std::abs instead of abs

* [autowarefoundation#1057] Implement Lateral Controller for Cargo ODD

* [autowarefoundation#1246] Resolve "Test case names currently use snake_case but should be CamelCase"

* [autowarefoundation#1325] Deactivate flaky smoke test in 'trajectory_follower_nodes'

* [autowarefoundation#1058] Add library code of longitudinal controller

* Fix build error for trajectory follower

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* Fix build error for trajectory follower nodes

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* [autowarefoundation#1272] Add AckermannControlCommand support to simple_planning_simulator

* [autowarefoundation#1058] Add Longitudinal Controller node

* [autowarefoundation#1058] Rename velocity_controller -> longitudinal_controller

* [autowarefoundation#1058] Update CMakeLists.txt for the longitudinal_controller_node

* [autowarefoundation#1058] Add smoke test python launch file

* [autowarefoundation#1058] Use LowPassFilter1d from trajectory_follower

* [autowarefoundation#1058] Use autoware_auto_msgs

* [autowarefoundation#1058] Changes for .auto (debug msg tmp fix, common func, tf listener)

* [autowarefoundation#1058] Remove unused parameters

* [autowarefoundation#1058] Fix ros test

* [autowarefoundation#1058] Rm default params from declare_parameters + use autoware types

* [autowarefoundation#1058] Use default param file to setup NodeOptions in the ros test

* [autowarefoundation#1058] Fix docstring

* [autowarefoundation#1058] Replace receiving a Twist with a VehicleKinematicState

* [autowarefoundation#1058] Change class variables format to m_ prefix

* [autowarefoundation#1058] Fix plugin name of LongitudinalController in CMakeLists.txt

* [autowarefoundation#1058] Fix copyright dates

* [autowarefoundation#1058] Reorder includes

* [autowarefoundation#1058] Add some tests (~89% coverage without disabling flaky tests)

* [autowarefoundation#1058] Add more tests (90+% coverage without disabling flaky tests)

* [autowarefoundation#1058] Use Float32MultiArrayDiagnostic message for debug and slope

* [autowarefoundation#1058] Calculate wheel_base value from vehicle parameters

* [autowarefoundation#1058] Cleanup redundant logger setting in tests

* [autowarefoundation#1058] Set ROS_DOMAIN_ID when running tests to prevent CI failures

* [autowarefoundation#1058] Remove TF listener and use published vehicle state instead

* [autowarefoundation#1058] Change smoke tests to use autoware_testing

* [autowarefoundation#1058] Add plotjuggler cfg for both lateral and longitudinal control

* [autowarefoundation#1058] Improve design documents

* [autowarefoundation#1058] Disable flaky test

* [autowarefoundation#1058] Properly transform vehicle state in longitudinal node

* [autowarefoundation#1058] Fix TF buffer of lateral controller

* [autowarefoundation#1058] Tuning of lateral controller for LGSVL

* [autowarefoundation#1058] Fix formating

* [autowarefoundation#1058] Fix /tf_static sub to be transient_local

* [autowarefoundation#1058] Fix yaw recalculation of reverse trajs in the lateral controller

* modify trajectory_follower for galactic build

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* [autowarefoundation#1379] Update trajectory_follower

* [autowarefoundation#1379] Update simple_planning_simulator

* [autowarefoundation#1379] Update trajectory_follower_nodes

* apply trajectory msg modification in control

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* move directory

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* remote control/trajectory_follower level dorectpry

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* remove .iv trajectory follower

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* use .auto trajectory_follower

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* remove .iv simple_planning_simulator & osqp_interface

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* use .iv simple_planning_simulator & osqp_interface

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* add tmp_autoware_auto_dependencies

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* tmporally add autoware_auto_msgs

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* apply .auto message split

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* fix build depend

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* fix packages using osqp

* fix autoware_auto_geometry

* ignore lint of some packages

* ignore ament_lint of some packages

* ignore lint/pre-commit of trajectory_follower_nodes

* disable unit tests of some packages

Co-authored-by: Maxime CLEMENT <maxime.clement@tier4.jp>
Co-authored-by: Joshua Whitley <josh.whitley@autoware.org>
Co-authored-by: Igor Bogoslavskyi <igor.bogoslavskyi@gmail.com>
Co-authored-by: MIURA Yasuyuki <kokosabu@gmail.com>
Co-authored-by: wep21 <border_goldenmarket@yahoo.co.jp>
Co-authored-by: tomoya.kimura <tomoya.kimura@tier4.jp>
Signed-off-by: tanaka3 <ttatcoder@outlook.jp>

* Fix message interface and tests of 'trajectory_follower_nodes' (autowarefoundation#617)

* Update longitudinal_controller_node to use VehicleOdometry

* Update lateral_controller_node for VehicleOdometry and SteeringReport

* Fix tests

Signed-off-by: tanaka3 <ttatcoder@outlook.jp>

* Change the topic name of the control_cmd to align them in trajectory_follower_node (autowarefoundation#659)

* Fix topic names

* Fix namespace

* Fix test codes

Signed-off-by: tanaka3 <ttatcoder@outlook.jp>

* Fix type of current odometry in trajectory_follower_node (autowarefoundation#666)

Signed-off-by: tanaka3 <ttatcoder@outlook.jp>

* [latlon muxer] fix gtest (autowarefoundation#670)

* fix gtest

* remove unchanged

Signed-off-by: tanaka3 <ttatcoder@outlook.jp>

* Update lateral controller (autowarefoundation#708)

* Fix parameter names of mpc_follower (autowarefoundation#1376)

* remove yaw_recalc param in mpc (autowarefoundation#1241) (autowarefoundation#1476)

* parameterize curvature num (autowarefoundation#1674) (autowarefoundation#1577)

* fix rosparam steer_rate_lim_degs to steer_rate_lim_dps in mpc_follower (autowarefoundation#1848)

* Fix spellcheck fail for some packages autowarefoundation#1842

* use interpolation::slerp (autowarefoundation#2161)

* Fix/mpc reset prev result (autowarefoundation#2185)

* add add guard (autowarefoundation#2184)

* add-mpc-optimization-status-print (autowarefoundation#2189)

* Apply ament_uncrustify

* Update control/trajectory_follower/src/qp_solver/qp_solver_osqp.cpp

Co-authored-by: Takamasa Horibe <horibe.takamasa@gmail.com>

Co-authored-by: Takamasa Horibe <horibe.takamasa@gmail.com>
Signed-off-by: tanaka3 <ttatcoder@outlook.jp>

* Use vehicle info utils (autowarefoundation#709)

* Use vehicle info utils and disable unit test

* Update trajectory_follower_nodes default parameters and reenable tests

* Separate vehicle info param file for test

Co-authored-by: Maxime CLEMENT <maxime.clement@tier4.jp>
Signed-off-by: tanaka3 <ttatcoder@outlook.jp>

* remove stop distance condition from stopState decision (autowarefoundation#1916) (autowarefoundation#715)

Signed-off-by: tanaka3 <ttatcoder@outlook.jp>

* velocity_controller sync to .iv develop latest (autowarefoundation#699)

* non extrapolate velocity in lerpTrajectory to avoid negative velocity just before vehicle stops (autowarefoundation#2033)

* Add keep braking function at driving state (autowarefoundation#2346)

* Add keep braking function at driving state

Signed-off-by: Makoto Kurihara <mkuri8m@gmail.com>

* Remove debug messages

Signed-off-by: Makoto Kurihara <mkuri8m@gmail.com>

* Fix format

Signed-off-by: Makoto Kurihara <mkuri8m@gmail.com>

* Feature/add doc for keep braking function at driving state (autowarefoundation#2366)

* Add the description of brake keeping

Signed-off-by: Makoto Kurihara <mkuri8m@gmail.com>

* Add the english document

Signed-off-by: Makoto Kurihara <mkuri8m@gmail.com>

* Improve description

Signed-off-by: Makoto Kurihara <mkuri8m@gmail.com>

* Add english description

Signed-off-by: Makoto Kurihara <mkuri8m@gmail.com>

Co-authored-by: Takayuki Murooka <takayuki5168@gmail.com>
Co-authored-by: Makoto Kurihara <mkuri8m@gmail.com>
Co-authored-by: Fumiya Watanabe <rej55.g@gmail.com>
Signed-off-by: tanaka3 <ttatcoder@outlook.jp>

* fix topic name in plot juggler (autowarefoundation#734)

Signed-off-by: tanaka3 <ttatcoder@outlook.jp>

* Fix unstable test in trajectory_follower_nodes (autowarefoundation#731)

* Added spin_some to store tf_buffer

* add more spin

* uncomment statement

* Remove temp file

* Update control/trajectory_follower_nodes/src/lateral_controller_node.cpp

Co-authored-by: Takamasa Horibe <horibe.takamasa@gmail.com>

Co-authored-by: Takamasa Horibe <horibe.takamasa@gmail.com>
Signed-off-by: tanaka3 <ttatcoder@outlook.jp>

Co-authored-by: Takamasa Horibe <horibe.takamasa@gmail.com>
Co-authored-by: Maxime CLEMENT <maxime.clement@tier4.jp>
Co-authored-by: Joshua Whitley <josh.whitley@autoware.org>
Co-authored-by: Igor Bogoslavskyi <igor.bogoslavskyi@gmail.com>
Co-authored-by: MIURA Yasuyuki <kokosabu@gmail.com>
Co-authored-by: wep21 <border_goldenmarket@yahoo.co.jp>
Co-authored-by: tomoya.kimura <tomoya.kimura@tier4.jp>
Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com>
Co-authored-by: Fumiya Watanabe <rej55.g@gmail.com>
Co-authored-by: Takayuki Murooka <takayuki5168@gmail.com>
Co-authored-by: Makoto Kurihara <mkuri8m@gmail.com>
Co-authored-by: Keisuke Shima <19993104+KeisukeShima@users.noreply.github.com>
  • Loading branch information
13 people committed Dec 7, 2021
1 parent 4d393e5 commit eb47ec5
Show file tree
Hide file tree
Showing 25 changed files with 4,809 additions and 0 deletions.
90 changes: 90 additions & 0 deletions control/trajectory_follower_nodes/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,90 @@
# Copyright 2021 The Autoware Foundation
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

cmake_minimum_required(VERSION 3.5)
project(trajectory_follower_nodes)

find_package(ament_cmake_auto REQUIRED)
ament_auto_find_build_dependencies()

set(LATERAL_CONTROLLER_NODE lateral_controller_node)
ament_auto_add_library(${LATERAL_CONTROLLER_NODE} SHARED
include/trajectory_follower_nodes/lateral_controller_node.hpp
src/lateral_controller_node.cpp
)

autoware_set_compile_options(${LATERAL_CONTROLLER_NODE})
# TODO(lateral_controller) : RCLCPP_ERROR_THROTTLE() has built-in old-style casts.
# TODO(lateral_controller) : Temporary workaround until this is fixed.
target_compile_options(${LATERAL_CONTROLLER_NODE} PRIVATE -Wno-error=old-style-cast)
rclcpp_components_register_node(${LATERAL_CONTROLLER_NODE}
PLUGIN "autoware::motion::control::trajectory_follower_nodes::LateralController"
EXECUTABLE ${LATERAL_CONTROLLER_NODE}_exe
)

set(LONGITUDINAL_CONTROLLER_NODE longitudinal_controller_node)
ament_auto_add_library(${LONGITUDINAL_CONTROLLER_NODE} SHARED
include/trajectory_follower_nodes/longitudinal_controller_node.hpp
src/longitudinal_controller_node.cpp
)

autoware_set_compile_options(${LONGITUDINAL_CONTROLLER_NODE})
# TODO(longitudinal_controller) : RCLCPP_ERROR_THROTTLE() has built-in old-style casts.
# TODO(longitudinal_controller) : Temporary workaround until this is fixed.
target_compile_options(${LONGITUDINAL_CONTROLLER_NODE} PRIVATE -Wno-error=old-style-cast)
rclcpp_components_register_node(${LONGITUDINAL_CONTROLLER_NODE}
PLUGIN "autoware::motion::control::trajectory_follower_nodes::LongitudinalController"
EXECUTABLE ${LONGITUDINAL_CONTROLLER_NODE}_exe
)

set(LATLON_MUXER_NODE latlon_muxer_node)
ament_auto_add_library(${LATLON_MUXER_NODE} SHARED
include/trajectory_follower_nodes/latlon_muxer_node.hpp
src/latlon_muxer_node.cpp
)

autoware_set_compile_options(${LATLON_MUXER_NODE})
# TODO(latlon_muxer) : RCLCPP_ERROR_THROTTLE() has built-in old-style casts.
# TODO(latlon_muxer) : Temporary workaround until this is fixed.
target_compile_options(${LATLON_MUXER_NODE} PRIVATE -Wno-error=old-style-cast)
rclcpp_components_register_node(${LATLON_MUXER_NODE}
PLUGIN "autoware::motion::control::trajectory_follower_nodes::LatLonMuxer"
EXECUTABLE ${LATLON_MUXER_NODE}_exe
)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
# Unit tests
set(TRAJECTORY_FOLLOWER_NODES_TEST test_trajectory_follower_nodes)
ament_add_gtest(${TRAJECTORY_FOLLOWER_NODES_TEST}
test/trajectory_follower_test_utils.hpp
test/test_latlon_muxer_node.cpp
test/test_lateral_controller_node.cpp
test/test_longitudinal_controller_node.cpp
)
ament_target_dependencies(${TRAJECTORY_FOLLOWER_NODES_TEST} fake_test_node)
autoware_set_compile_options(${TRAJECTORY_FOLLOWER_NODES_TEST})
target_link_libraries(${TRAJECTORY_FOLLOWER_NODES_TEST} ${LATLON_MUXER_NODE} ${LATERAL_CONTROLLER_NODE} ${LONGITUDINAL_CONTROLLER_NODE})

#find_package(autoware_testing REQUIRED)
#add_smoke_test(${PROJECT_NAME} ${LATLON_MUXER_NODE}_exe PARAM_FILENAME latlon_muxer_defaults.yaml)
#add_smoke_test(${PROJECT_NAME} ${LATERAL_CONTROLLER_NODE}_exe PARAM_FILENAME lateral_controller_defaults.yaml)
#add_smoke_test(${PROJECT_NAME} ${LONGITUDINAL_CONTROLLER_NODE}_exe PARAM_FILENAME longitudinal_controller_defaults.yaml)
endif()

ament_auto_package(
INSTALL_TO_SHARE
param
)
Original file line number Diff line number Diff line change
@@ -0,0 +1,276 @@
<?xml version='1.0' encoding='UTF-8'?>
<root version="2.3.8">
<tabbed_widget name="Main Window" parent="main_window">
<Tab containers="1" tab_name="Lateral Controller">
<Container>
<DockSplitter orientation="-" count="2" sizes="0.502237;0.497763">
<DockSplitter orientation="|" count="3" sizes="0.333333;0.333333;0.333333">
<DockArea name="Lateral Controller Info">
<plot mode="TimeSeries" style="Lines">
<range bottom="-1.152264" top="1.022526" right="118.796638" left="76.172500"/>
<limitY/>
<curve name="/control/trajectory_follower/lateral/diagnostic/diag_array/data.5" color="#1f77b4">
<transform alias="lateral error" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
<curve name="/control/trajectory_follower/lateral/diagnostic/diag_array/data.8" color="#d62728">
<transform alias="yaw error" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
<curve name="/control/trajectory_follower/lateral/diagnostic/diag_array/data.0" color="#1ac938">
<transform alias="steer cmd (final)" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
<curve name="/control/trajectory_follower/lateral/diagnostic/diag_array/data.2" color="#ff7f0e">
<transform alias="steer cmd (FF-filtered)" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
<curve name="/control/trajectory_follower/lateral/diagnostic/diag_array/data.3" color="#f14cc1">
<transform alias="steer cmd (FF-raw)" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
<curve name="/control/trajectory_follower/lateral/diagnostic/diag_array/data.4" color="#9467bd">
<transform alias="steer measured" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
<curve name="/control/trajectory_follower/lateral/diagnostic/diag_array/data.1" color="#17becf">
<transform alias="steer cmd (mpc-raw)" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
</plot>
</DockArea>
<DockArea name="Velocity">
<plot mode="TimeSeries" style="Lines">
<range bottom="-0.069444" top="2.847222" right="118.796638" left="76.172500"/>
<limitY/>
<curve name="/control/trajectory_follower/lateral/diagnostic/diag_array/data.9" color="#1f77b4">
<transform alias="trajectory velocity" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
<curve name="/control/trajectory_follower/lateral/diagnostic/diag_array/data.10" color="#d62728">
<transform alias="current velocity" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
</plot>
</DockArea>
<DockArea name="path curvature">
<plot mode="TimeSeries" style="Lines">
<range bottom="-0.460804" top="0.984813" right="118.796638" left="76.172500"/>
<limitY/>
<curve name="/control/trajectory_follower/lateral/diagnostic/diag_array/data.14" color="#d62728">
<transform alias="smoothed" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
<curve name="/control/trajectory_follower/lateral/diagnostic/diag_array/data.15" color="#1f77b4">
<transform alias="raw" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
</plot>
</DockArea>
</DockSplitter>
<DockSplitter orientation="|" count="3" sizes="0.33211;0.33578;0.33211">
<DockArea name="angular-velocity converted from">
<plot mode="TimeSeries" style="Lines">
<range bottom="-0.045019" top="1.491571" right="118.796638" left="76.172500"/>
<limitY/>
<curve name="/control/trajectory_follower/lateral/diagnostic/diag_array/data.11" color="#1ac938">
<transform alias="steering cmd" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
<curve name="/control/trajectory_follower/lateral/diagnostic/diag_array/data.12" color="#ff7f0e">
<transform alias="steering measured " name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
<curve name="/control/trajectory_follower/lateral/diagnostic/diag_array/data.13" color="#d62728">
<transform alias="path curvature (smoothed)" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
<curve name="/control/trajectory_follower/lateral/diagnostic/diag_array/data.17" color="#1f77b4">
<transform alias="steering predicted" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
</plot>
</DockArea>
<DockArea name="yaw">
<plot mode="TimeSeries" style="Lines">
<range bottom="-3.295688" top="3.281428" right="118.796638" left="76.172500"/>
<limitY/>
<curve name="/control/trajectory_follower/lateral/diagnostic/diag_array/data.7" color="#1ac938">
<transform alias="desired yaw" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
<curve name="/control/trajectory_follower/lateral/diagnostic/diag_array/data.6" color="#ff7f0e">
<transform alias="current yaw" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
</plot>
</DockArea>
<DockArea name="control mode (1: Auto, 2: Manual, 3: Disengaged, 4: Not Ready)">
<plot mode="TimeSeries" style="Lines">
<range bottom="0.900000" top="1.100000" right="118.791728" left="76.166273"/>
<limitY/>
<curve name="/vehicle/state_report/mode" color="#1f77b4"/>
</plot>
</DockArea>
</DockSplitter>
</DockSplitter>
</Container>
</Tab>
<Tab containers="1" tab_name="Longitudinal Controller">
<Container>
<DockSplitter orientation="-" count="2" sizes="0.502237;0.497763">
<DockSplitter orientation="|" count="2" sizes="0.498778;0.501222">
<DockArea name="Longitudinal Controller Info">
<plot mode="TimeSeries" style="Lines">
<range bottom="-46.710209" top="91.855136" right="109.929097" left="76.129089"/>
<limitY/>
<curve name="/control/trajectory_follower/longitudinal/diagnostic/diag_array/data.3" color="#1ac938">
<transform alias="FF" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
<curve name="/control/trajectory_follower/longitudinal/diagnostic/diag_array/data.14" color="#ff7f0e">
<transform alias="FF+FB" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
<curve name="/control/trajectory_follower/longitudinal/diagnostic/diag_array/data.19" color="#f14cc1">
<transform alias="FB-P" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
<curve name="/control/trajectory_follower/longitudinal/diagnostic/diag_array/data.20" color="#9467bd">
<transform alias="FB-I" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
<curve name="/control/trajectory_follower/longitudinal/diagnostic/diag_array/data.21" color="#17becf">
<transform alias="FB-D" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
<curve name="/control/trajectory_follower/longitudinal/diagnostic/diag_array/data.15" color="#bcbd22">
<transform alias="acc filtered" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
<curve name="/control/trajectory_follower/longitudinal/diagnostic/diag_array/data.16" color="#1f77b4">
<transform alias="jerk filtered" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
<curve name="/control/trajectory_follower/longitudinal/diagnostic/diag_array/data.17" color="#d62728">
<transform alias="slope added" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
<curve name="/control/trajectory_follower/longitudinal/diagnostic/diag_array/data.18" color="#1ac938">
<transform alias="final" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
<curve name="/control/trajectory_follower/longitudinal/diagnostic/diag_array/data.25" color="#ff7f0e">
<transform alias="calculated" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
</plot>
</DockArea>
<DockArea name="State">
<plot mode="TimeSeries" style="Lines">
<range bottom="-0.050000" top="2.050000" right="109.929097" left="76.129089"/>
<limitY/>
<curve name="/control/trajectory_follower/longitudinal/diagnostic/diag_array/data.13" color="#d62728">
<transform alias="0:Drive 1:Stopping 2:Stopped 3:Emergency" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
</plot>
</DockArea>
</DockSplitter>
<DockArea name="Velocity">
<plot mode="TimeSeries" style="Lines">
<range bottom="-0.070625" top="2.895625" right="109.929097" left="76.129089"/>
<limitY/>
<curve name="/control/trajectory_follower/longitudinal/diagnostic/diag_array/data.2" color="#17becf">
<transform alias="target" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
<curve name="/control/trajectory_follower/longitudinal/diagnostic/diag_array/data.1" color="#9467bd">
<transform alias="current" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
<curve name="/control/trajectory_follower/longitudinal/diagnostic/diag_array/data.4" color="#bcbd22">
<transform alias="closest" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
<curve name="/control/trajectory_follower/longitudinal/diagnostic/diag_array/data.24" color="#1f77b4">
<transform alias="predicted" name="Scale/Offset">
<options value_scale="1.0" time_offset="0" value_offset="0"/>
</transform>
</curve>
</plot>
</DockArea>
</DockSplitter>
</Container>
</Tab>
<currentTabIndex index="0"/>
</tabbed_widget>
<use_relative_time_offset enabled="1"/>
<!-- - - - - - - - - - - - - - - -->
<!-- - - - - - - - - - - - - - - -->
<Plugins>
<plugin ID="DataLoad CSV">
<default time_axis=""/>
</plugin>
<plugin ID="DataLoad ROS2 bags">
<use_header_stamp value="false"/>
<discard_large_arrays value="true"/>
<max_array_size value="99"/>
</plugin>
<plugin ID="DataLoad ULog"/>
<plugin ID="ROS2 Topic Subscriber">
<use_header_stamp value="false"/>
<discard_large_arrays value="false"/>
<max_array_size value="true"/>
<selected_topics>
<topic name="/control/trajectory_follower/longitudinal/diagnostic"/>
<topic name="/control/trajectory_follower/lateral/diagnostic"/>
<topic name="/vehicle/state_report"/>
</selected_topics>
</plugin>
<plugin ID="UDP Server"/>
<plugin ID="WebSocket Server"/>
<plugin ID="ZMQ Subscriber"/>
<plugin status="idle" ID="CSV Exporter"/>
<plugin status="idle" ID="ROS2 Topic Re-Publisher"/>
</Plugins>
<!-- - - - - - - - - - - - - - - -->
<previouslyLoaded_Datafiles/>
<previouslyLoaded_Streamer name="ROS2 Topic Subscriber"/>
<!-- - - - - - - - - - - - - - - -->
<customMathEquations/>
<snippets/>
<!-- - - - - - - - - - - - - - - -->
</root>

Loading

0 comments on commit eb47ec5

Please sign in to comment.