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

feat: add simple planning simulator package #5

Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
Show all changes
64 commits
Select commit Hold shift + click to select a range
8e97427
release v0.4.0
mitsudome-r Sep 18, 2020
bbcddb4
remove ROS1 packages temporarily
mitsudome-r Sep 29, 2020
edc7b36
add sample ros2 packages
mitsudome-r Sep 29, 2020
5fac7eb
add COLCON_IGNORE to ros1 packages
mitsudome-r Oct 8, 2020
c41b710
Fix simple planning simulator (#26)
TakaHoribe Oct 13, 2020
e14ecad
[simple_planning_simulator] add rostopic relay in launch file (#117)
mitsudome-r Nov 24, 2020
7406784
Adjust copyright notice on 532 out of 699 source files (#143)
nnmm Dec 3, 2020
7aa3365
Use quotes for includes where appropriate (#144)
nnmm Dec 7, 2020
c2ecb34
Run uncrustify on the entire Pilot.Auto codebase (#151)
nnmm Dec 8, 2020
ffab21d
reduce terminal ouput for better error message visibility (#200)
mitsudome-r Dec 23, 2020
fc3691f
Use trajectory for z position source (#243)
wep21 Dec 24, 2020
a97a775
Ros2 v0.8.0 engage (#342)
wep21 Feb 17, 2021
4dcfe97
Ros2 v0.8.0 fix packages (#351)
tkimura4 Feb 24, 2021
bdd1791
Rename ROS-related .yaml to .param.yaml (#352)
kenji-miyake Feb 24, 2021
bf134df
Fix typo in simulator module (#439)
kmiya Mar 16, 2021
b222d75
add use_sim-time option (#454)
tkimura4 Mar 26, 2021
4ef120c
Format launch files (#1219)
kenji-miyake Mar 30, 2021
0ccd6f1
Fix rolling build errors (#1225)
kenji-miyake Apr 5, 2021
9c2f176
Sync public repo (#1228)
mitsudome-r Apr 5, 2021
2e3c97d
Remove use_sim_time for set_parameter (#1260)
wep21 Apr 26, 2021
0289c8f
Refactor vehicle info util (#1305)
kenji-miyake May 11, 2021
c5f4978
Fix lint errors (#1378)
kenji-miyake May 25, 2021
52b35cf
Add pre-commit (#1560)
KeisukeShima Jul 19, 2021
04ccb95
Add markdownlint and prettier (#1661)
kenji-miyake Jul 20, 2021
5b7f460
add cov pub in psim (#1732)
k0suke-murakami Jul 30, 2021
f74b212
Fix -Wunused-parameter (#1836)
kenji-miyake Aug 14, 2021
c506ed7
fix some typos (#1941)
h-ohta Aug 25, 2021
4f99ca0
Add autoware api (#1979)
isamu-takagi Aug 31, 2021
7a3670e
add sort-package-xml hook in pre-commit (#1881)
KeisukeShima Sep 9, 2021
467c390
Feature/add ideal accel model interface (#1894)
mkuri Oct 21, 2021
7a8aa72
Change formatter to clang-format and black (#2332)
kenji-miyake Nov 2, 2021
b96e68b
Add COLCON_IGNORE (#500)
kenji-miyake Nov 4, 2021
789899e
Back port .auto control packages (#571)
TakaHoribe Nov 11, 2021
059f0e1
[simple planning simulator]change type of msg (#590)
tkimura4 Nov 12, 2021
82666d7
[autoware_vehicle_rviz_plugin/route_handler/simple_planning_simulator…
tkimura4 Nov 12, 2021
ee7955b
update to support velocity report header (#655)
TakaHoribe Nov 15, 2021
cc7525d
adapt to actuation cmd/status as control msg (#646)
taikitanaka3 Nov 16, 2021
b47409b
FIx vehicle status topic name/type (#658)
tkimura4 Nov 16, 2021
9068bd1
fix topic name (#674)
TakaHoribe Nov 17, 2021
4845cd6
Fix psim param path (#696)
isamu-takagi Nov 18, 2021
40add7f
Fix/psim topics emergency handler awapi (#702)
taikitanaka3 Nov 18, 2021
bc9c8c5
Auto/add turn indicators and hazards (#717)
kyoichi-sugahara Nov 19, 2021
336c5f9
[simple_planning_simulator]fix bug (#727)
tkimura4 Nov 24, 2021
530a622
fix gear process in sim (#728)
tkimura4 Nov 24, 2021
8168271
Fix for integration test (#732)
isamu-takagi Nov 25, 2021
69ad7af
Simple planning simulator update for latest develop (#735)
TakaHoribe Nov 26, 2021
4acd06b
Fix acceleration for reverse (#737)
rej55 Nov 29, 2021
764a4e7
Merge branch 'tier4/proposal' into 1-add-simple-planning-simulator
1222-takeshi Dec 2, 2021
7731f62
ci(pre-commit): autofix
pre-commit-ci[bot] Dec 2, 2021
bf2fc6b
Merge branch 'tier4/proposal' into 1-add-simple-planning-simulator
1222-takeshi Dec 2, 2021
373f7a4
Merge branch 'tier4/proposal' into 1-add-simple-planning-simulator
1222-takeshi Dec 3, 2021
a6f18eb
remove tests
tkimura4 Dec 6, 2021
3c67709
Merge branch 'tier4/proposal' into 1-add-simple-planning-simulator
tkimura4 Dec 6, 2021
17b40e0
Merge branch 'tier4/proposal' into 1-add-simple-planning-simulator
tkimura4 Dec 6, 2021
e1abab4
Revert "ci(pre-commit): autofix"
tkimura4 Dec 6, 2021
2306e18
Merge branch 'tier4/proposal' into 1-add-simple-planning-simulator
tkimura4 Dec 6, 2021
e277c4c
fix format
tkimura4 Dec 6, 2021
83cf537
Merge branch '1-add-simple-planning-simulator' of github.com:tkimura4…
tkimura4 Dec 6, 2021
72d50cf
Merge branch 'tier4/proposal' into 1-add-simple-planning-simulator
tkimura4 Dec 6, 2021
7c1f7c1
Merge branch 'tier4/proposal' into 1-add-simple-planning-simulator
tkimura4 Dec 6, 2021
9a8ae1e
Merge branch 'tier4/proposal' into 1-add-simple-planning-simulator
tkimura4 Dec 6, 2021
d947eee
fix autoware_api_utils
tkimura4 Dec 6, 2021
68b5ded
Merge branch 'tier4/proposal' into 1-add-simple-planning-simulator
tkimura4 Dec 6, 2021
6fb3e65
Merge branch 'tier4/proposal' into 1-add-simple-planning-simulator
tkimura4 Dec 6, 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
Prev Previous commit
Next Next commit
add COLCON_IGNORE to ros1 packages
Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp>
  • Loading branch information
mitsudome-r authored and tkimura4 committed Nov 30, 2021
commit 5fac7eb3deca883b5100d10521eef4b81275a92c
29 changes: 29 additions & 0 deletions simulator/simple_planning_simulator/config/simulator_model.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
acc_time_constant: 0.1
acc_time_delay: 0.1
accel_rate: 7.0
add_measurement_noise: true
angvel_lim: 3.0
angvel_noise_stddev: 0.0
angvel_rate: 1.0
angvel_time_constant: 0.5
angvel_time_delay: 0.2
initial_engage_state: true
pos_noise_stddev: 0.01
rpy_noise_stddev: 0.0001
sim_steering_gear_ratio: 15.0
steer_lim: 1.0
steer_noise_stddev: 0.0001
steer_rate_lim: 5.0
steer_time_constant: 0.27
steer_time_delay: 0.24
tread_length: 1.0

# Option for vehicle_model_type:
# - IDEAL_STEER : reads velocity command. The steering and velocity changes exactly the same as commanded.
# - DELAY_STEER : reads velocity command. The steering and velocity changes with delay model.
# - DELAY_STEER_ACC : reads acceleration command. The steering and acceleration changes with delay model.
vehicle_model_type: DELAY_STEER_ACC
vel_lim: 50.0
vel_noise_stddev: 0.0
vel_time_constant: 0.61
vel_time_delay: 0.25
Original file line number Diff line number Diff line change
@@ -0,0 +1,82 @@
<launch>
<!-- simple_planning_simulator parameters -->
<arg name="loop_rate" default="50.0"/>
<arg name="simulation_frame_id" default="base_link"/>
<arg name="map_frame_id" default="map"/>
<arg name="initialize_source" default="RVIZ"/>
<arg name="use_waypoints_for_z_position_source" default="true"/>

<!-- model parameters -->
<arg name="vehicle_model_type" default="IDEAL_ACCEL"/>

<arg name="tread_length" default="1.0"/>
<arg name="angvel_lim" default="3.0"/>
<arg name="vel_lim" default="30.0"/>
<arg name="steer_lim" default="1.0"/>
<arg name="angvel_rate" default="1.0"/>
<arg name="steer_rate_lim" default="0.3"/>
<arg name="vel_time_delay" default="0.25"/>
<arg name="vel_time_constant" default="0.61"/>
<arg name="steer_time_delay" default="0.24"/>
<arg name="steer_time_constant" default="0.27"/>
<arg name="angvel_time_delay" default="0.2"/>
<arg name="angvel_time_constant" default="0.5"/>

<arg name="add_measurement_noise" default="true"/>
<arg name="pos_noise_stddev" default="0.01"/>
<arg name="vel_noise_stddev" default="0.01"/>
<arg name="rpy_noise_stddev" default="0.0001"/>
<arg name="angvel_noise_stddev" default="0.001"/>
<arg name="steer_noise_stddev" default="0.0001"/>

<arg name="initial_engage_state" default="true"/>

<!-- simple_planning_simulator node -->
<node pkg="simple_planning_simulator" type="simple_planning_simulator" name="simple_planning_simulator" output="screen">
<remap from="/base_trajectory" to="/planning/scenario_planning/trajectory" />
<remap from="~output/current_pose" to="current_pose" />
<remap from="~output/current_velocity" to="/sim/velocity" />
<remap from="~output/status" to="/sim/status" />
<remap from="~output/control_mode" to="/vehicle/status/control_mode" />
<remap from="~input/vehicle_cmd" to="/sim/vehicle_cmd" />
<remap from="~input/turn_signal_cmd" to="/control/turn_signal_cmd" />
<remap from="~input/initial_twist" to="/initialtwist" />
<remap from="~input/engage" to="/vehicle/engage" />

<param name="loop_rate" value="$(arg loop_rate)"/>
<param name="simulation_frame_id" value="$(arg simulation_frame_id)"/>
<param name="map_frame_id" value="$(arg map_frame_id)"/>
<param name="add_measurement_noise" value="$(arg add_measurement_noise)"/>
<param name="initialize_source" value="$(arg initialize_source)"/>
<param name="use_waypoints_for_z_position_source" value="$(arg use_waypoints_for_z_position_source)"/>

<param name="tread_length" value="$(arg tread_length)"/>
<param name="angvel_lim" value="$(arg angvel_lim)"/>
<param name="vel_lim" value="$(arg vel_lim)"/>
<param name="steer_lim" value="$(arg steer_lim)"/>
<param name="angvel_rate" value="$(arg angvel_rate)"/>
<param name="steer_rate_lim" value="$(arg steer_rate_lim)"/>
<param name="vel_time_delay" value="$(arg vel_time_delay)"/>
<param name="vel_time_constant" value="$(arg vel_time_constant)"/>
<param name="steer_time_delay" value="$(arg steer_time_delay)"/>
<param name="steer_time_constant" value="$(arg steer_time_constant)"/>
<param name="angvel_time_delay" value="$(arg angvel_time_delay)"/>
<param name="angvel_time_constant" value="$(arg angvel_time_constant)"/>

<param name="vehicle_model_type" value="$(arg vehicle_model_type)"/>
<param name="pos_noise_stddev" value="$(arg pos_noise_stddev)"/>
<param name="vel_noise_stddev" value="$(arg vel_noise_stddev)"/>
<param name="rpy_noise_stddev" value="$(arg rpy_noise_stddev)"/>
<param name="angvel_noise_stddev" value="$(arg angvel_noise_stddev)"/>
<param name="steer_noise_stddev" value="$(arg steer_noise_stddev)"/>

<param name="initial_engage_state" value="$(arg initial_engage_state)"/>
</node>


<!-- sim pacmod interface node -->
<node pkg="as" type="pacmod_sim_interface" name="sim_pacmod" output="screen"/>



</launch>