Skip to content

Commit d842842

Browse files
committed
테스트 드가자~
1 parent 45403d3 commit d842842

36 files changed

+1653
-456
lines changed

turtlebot3_gazebo/CMakeLists.txt

Lines changed: 21 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,8 @@ endif()
2020
# Find ament packages and libraries for ament and system dependencies
2121
################################################################################
2222
find_package(ament_cmake REQUIRED)
23-
find_package(ros_gz_sim REQUIRED)
23+
find_package(gz-sim8 REQUIRED)
24+
find_package(gz-plugin2 REQUIRED)
2425
find_package(geometry_msgs REQUIRED)
2526
find_package(nav_msgs REQUIRED)
2627
find_package(rclcpp REQUIRED)
@@ -40,37 +41,33 @@ include_directories(
4041
)
4142

4243
set(dependencies
43-
"geometry_msgs"
44-
"nav_msgs"
45-
"rclcpp"
46-
"sensor_msgs"
47-
"tf2"
44+
geometry_msgs
45+
nav_msgs
46+
rclcpp
47+
sensor_msgs
48+
tf2
4849
)
4950

50-
set(EXEC_NAME "turtlebot3_drive")
51+
add_executable(turtlebot3_drive src/turtlebot3_drive.cpp)
52+
ament_target_dependencies(turtlebot3_drive ${dependencies})
5153

52-
add_executable(${EXEC_NAME} src/turtlebot3_drive.cpp)
53-
ament_target_dependencies(${EXEC_NAME} ${dependencies})
54+
add_library(obstacles SHARED src/obstacles.cpp)
55+
ament_target_dependencies(obstacles gz-sim8 gz-plugin2)
5456

55-
# add_library(traffic_light_plugin SHARED src/traffic_light_plugin.cpp)
56-
# target_link_libraries(traffic_light_plugin ${GAZEBO_LIBRARIES})
57+
add_library(obstacle1 SHARED src/obstacle1.cpp)
58+
ament_target_dependencies(obstacle1 gz-sim8 gz-plugin2)
5759

58-
# add_library(traffic_bar_plugin SHARED src/traffic_bar_plugin.cpp)
59-
# target_link_libraries(traffic_bar_plugin ${GAZEBO_LIBRARIES})
60-
61-
# add_library(obstacle1 SHARED src/obstacle1.cpp)
62-
# target_link_libraries(obstacle1 ${GAZEBO_LIBRARIES})
63-
64-
# add_library(obstacle2 SHARED src/obstacle2.cpp)
65-
# target_link_libraries(obstacle2 ${GAZEBO_LIBRARIES})
66-
67-
# add_library(obstacles SHARED src/obstacles.cpp)
68-
# target_link_libraries(obstacles ${GAZEBO_LIBRARIES})
60+
add_library(obstacle2 SHARED src/obstacle2.cpp)
61+
ament_target_dependencies(obstacle2 gz-sim8 gz-plugin2)
6962

7063
################################################################################
7164
# Install
7265
################################################################################
73-
install(TARGETS ${EXEC_NAME}
66+
install(TARGETS
67+
turtlebot3_drive
68+
obstacles
69+
obstacle1
70+
obstacle2
7471
DESTINATION lib/${PROJECT_NAME}
7572
)
7673

@@ -86,7 +83,7 @@ install(DIRECTORY include/
8683
# Macro for ament package
8784
################################################################################
8885
ament_export_include_directories(include)
89-
ament_export_dependencies(gazebo_ros_pkgs)
86+
ament_export_dependencies(gz-sim8)
9087
ament_export_dependencies(geometry_msgs)
9188
ament_export_dependencies(nav_msgs)
9289
ament_export_dependencies(rclcpp)
Lines changed: 35 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -1,38 +1,41 @@
1-
// Copyright 2012 Open Source Robotics Foundation
2-
//
3-
// Licensed under the Apache License, Version 2.0 (the "License");
4-
// you may not use this file except in compliance with the License.
5-
// You may obtain a copy of the License at
6-
//
7-
// http://www.apache.org/licenses/LICENSE-2.0
8-
//
9-
// Unless required by applicable law or agreed to in writing, software
10-
// distributed under the License is distributed on an "AS IS" BASIS,
11-
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12-
// See the License for the specific language governing permissions and
13-
// limitations under the License.
14-
//
15-
// Author: Ryan Shim
16-
17-
#ifndef TURTLEBOT3_GAZEBO__OBSTACLE1_HPP_
18-
#define TURTLEBOT3_GAZEBO__OBSTACLE1_HPP_
19-
20-
#include <ignition/math.hh>
21-
#include <gazebo/common/common.hh>
22-
#include <gazebo/gazebo.hh>
23-
#include <gazebo/physics/physics.hh>
24-
25-
namespace gazebo
1+
#ifndef TURTLEBOT3_GAZEBO_OBSTACLE1_PLUGIN_HPP
2+
#define TURTLEBOT3_GAZEBO_OBSTACLE1_PLUGIN_HPP
3+
4+
#include <gz/sim/System.hh>
5+
#include <gz/sim/Model.hh>
6+
#include <gz/sim/EntityComponentManager.hh>
7+
#include <gz/sim/components/Pose.hh>
8+
#include <gz/math/Vector3.hh>
9+
#include <gz/math/Quaternion.hh>
10+
#include <chrono>
11+
12+
namespace turtlebot3_gazebo
2613
{
27-
class Obstacle1 : public ModelPlugin
14+
15+
class Obstacle1Plugin
16+
: public gz::sim::System,
17+
public gz::sim::ISystemConfigure,
18+
public gz::sim::ISystemPreUpdate
2819
{
2920
public:
30-
void Load(physics::ModelPtr _parent, sdf::ElementPtr /*_sdf*/) override;
21+
Obstacle1Plugin() = default;
22+
~Obstacle1Plugin() override = default;
23+
24+
void Configure(
25+
const gz::sim::Entity &entity,
26+
const std::shared_ptr<const sdf::Element> &sdf,
27+
gz::sim::EntityComponentManager &ecm,
28+
gz::sim::EventManager &eventMgr) override;
29+
30+
void PreUpdate(
31+
const gz::sim::UpdateInfo &info,
32+
gz::sim::EntityComponentManager &ecm) override;
3133

3234
private:
33-
physics::ModelPtr model;
34-
event::ConnectionPtr updateConnection;
35+
gz::sim::Model model{gz::sim::kNullEntity};
36+
std::chrono::steady_clock::time_point startTime;
3537
};
36-
GZ_REGISTER_MODEL_PLUGIN(Obstacle1);
37-
} // namespace gazebo
38-
#endif // TURTLEBOT3_GAZEBO__OBSTACLE1_HPP_
38+
39+
} // namespace turtlebot3_gazebo
40+
41+
#endif // TURTLEBOT3_GAZEBO_OBSTACLE1_PLUGIN_HPP
Lines changed: 35 additions & 33 deletions
Original file line numberDiff line numberDiff line change
@@ -1,39 +1,41 @@
1-
// Copyright 2012 Open Source Robotics Foundation
2-
//
3-
// Licensed under the Apache License, Version 2.0 (the "License");
4-
// you may not use this file except in compliance with the License.
5-
// You may obtain a copy of the License at
6-
//
7-
// http://www.apache.org/licenses/LICENSE-2.0
8-
//
9-
// Unless required by applicable law or agreed to in writing, software
10-
// distributed under the License is distributed on an "AS IS" BASIS,
11-
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12-
// See the License for the specific language governing permissions and
13-
// limitations under the License.
14-
//
15-
// Author: Ryan Shim
16-
17-
#ifndef TURTLEBOT3_GAZEBO__OBSTACLE2_HPP_
18-
#define TURTLEBOT3_GAZEBO__OBSTACLE2_HPP_
19-
20-
#include <ignition/math.hh>
21-
#include <gazebo/common/common.hh>
22-
#include <gazebo/gazebo.hh>
23-
#include <gazebo/physics/physics.hh>
24-
25-
namespace gazebo
1+
#ifndef TURTLEBOT3_GAZEBO_OBSTACLE2_PLUGIN_HPP
2+
#define TURTLEBOT3_GAZEBO_OBSTACLE2_PLUGIN_HPP
3+
4+
#include <gz/sim/System.hh>
5+
#include <gz/sim/Model.hh>
6+
#include <gz/sim/EntityComponentManager.hh>
7+
#include <gz/sim/components/Pose.hh>
8+
#include <gz/math/Vector3.hh>
9+
#include <gz/math/Quaternion.hh>
10+
#include <chrono>
11+
12+
namespace turtlebot3_gazebo
2613
{
27-
class Obstacle2 : public ModelPlugin
14+
15+
class Obstacle2Plugin
16+
: public gz::sim::System,
17+
public gz::sim::ISystemConfigure,
18+
public gz::sim::ISystemPreUpdate
2819
{
2920
public:
30-
Obstacle2() = default;
31-
void Load(physics::ModelPtr _parent, sdf::ElementPtr /*_sdf*/) override;
21+
Obstacle1Plugin() = default;
22+
~Obstacle1Plugin() override = default;
23+
24+
void Configure(
25+
const gz::sim::Entity &entity,
26+
const std::shared_ptr<const sdf::Element> &sdf,
27+
gz::sim::EntityComponentManager &ecm,
28+
gz::sim::EventManager &eventMgr) override;
29+
30+
void PreUpdate(
31+
const gz::sim::UpdateInfo &info,
32+
gz::sim::EntityComponentManager &ecm) override;
3233

3334
private:
34-
physics::ModelPtr model;
35-
event::ConnectionPtr updateConnection;
35+
gz::sim::Model model{gz::sim::kNullEntity};
36+
std::chrono::steady_clock::time_point startTime;
3637
};
37-
GZ_REGISTER_MODEL_PLUGIN(Obstacle2);
38-
} // namespace gazebo
39-
#endif // TURTLEBOT3_GAZEBO__OBSTACLE2_HPP_
38+
39+
} // namespace turtlebot3_gazebo
40+
41+
#endif // TURTLEBOT3_GAZEBO_OBSTACLE2_PLUGIN_HPP

turtlebot3_gazebo/include/turtlebot3_gazebo/obstacles.hpp

Lines changed: 29 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -17,25 +17,40 @@
1717
#ifndef TURTLEBOT3_GAZEBO__OBSTACLES_HPP_
1818
#define TURTLEBOT3_GAZEBO__OBSTACLES_HPP_
1919

20-
#include <ignition/math.hh>
21-
#include <gazebo/common/common.hh>
22-
#include <gazebo/gazebo.hh>
23-
#include <gazebo/physics/physics.hh>
20+
#include <gz/sim/System.hh>
21+
#include <gz/sim/Model.hh>
22+
#include <gz/sim/EntityComponentManager.hh>
23+
#include <gz/sim/components/WorldPose.hh>
24+
#include <gz/plugin/Register.hh>
25+
#include <gz/math/Pose3.hh>
26+
#include <gz/math/Vector3.hh>
27+
#include <gz/math/Quaternion.hh>
28+
#include <chrono>
2429

25-
#define PI 3.141592
26-
27-
namespace gazebo
30+
namespace turtlebot3_gazebo
2831
{
29-
class Obstacles : public ModelPlugin
32+
33+
class ObstaclesPlugin
34+
: public gz::sim::System,
35+
public gz::sim::ISystemConfigure,
36+
public gz::sim::ISystemPreUpdate
3037
{
3138
public:
32-
Obstacles() = default;
33-
void Load(physics::ModelPtr _parent, sdf::ElementPtr /*_sdf*/) override;
39+
void Configure(
40+
const gz::sim::Entity &entity,
41+
const std::shared_ptr<const sdf::Element> &sdf,
42+
gz::sim::EntityComponentManager &ecm,
43+
gz::sim::EventManager &eventMgr) override;
44+
45+
void PreUpdate(
46+
const gz::sim::UpdateInfo &info,
47+
gz::sim::EntityComponentManager &ecm) override;
3448

3549
private:
36-
physics::ModelPtr model;
37-
event::ConnectionPtr updateConnection;
50+
gz::sim::Model model{gz::sim::kNullEntity};
51+
std::chrono::steady_clock::time_point startTime;
3852
};
39-
GZ_REGISTER_MODEL_PLUGIN(Obstacles);
40-
} // namespace gazebo
53+
54+
} // namespace turtlebot3_gazebo
55+
4156
#endif // TURTLEBOT3_GAZEBO__OBSTACLES_HPP_
Lines changed: 101 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,101 @@
1+
#!/usr/bin/env python3
2+
#
3+
# Copyright 2019 ROBOTIS CO., LTD.
4+
#
5+
# Licensed under the Apache License, Version 2.0 (the "License");
6+
# you may not use this file except in compliance with the License.
7+
# You may obtain a copy of the License at
8+
#
9+
# http://www.apache.org/licenses/LICENSE-2.0
10+
#
11+
# Unless required by applicable law or agreed to in writing, software
12+
# distributed under the License is distributed on an "AS IS" BASIS,
13+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14+
# See the License for the specific language governing permissions and
15+
# limitations under the License.
16+
#
17+
# Authors: Joep Tool
18+
19+
import os
20+
21+
from ament_index_python.packages import get_package_share_directory
22+
from launch import LaunchDescription
23+
from launch.actions import AppendEnvironmentVariable
24+
from launch.actions import IncludeLaunchDescription
25+
from launch.launch_description_sources import PythonLaunchDescriptionSource
26+
from launch.substitutions import LaunchConfiguration
27+
from launch_ros.actions import Node
28+
29+
def generate_launch_description():
30+
launch_file_dir = os.path.join(get_package_share_directory('turtlebot3_gazebo'), 'launch')
31+
ros_gz_sim = get_package_share_directory('ros_gz_sim')
32+
33+
use_sim_time = LaunchConfiguration('use_sim_time', default='true')
34+
x_pose = LaunchConfiguration('x_pose', default='0.0')
35+
y_pose = LaunchConfiguration('y_pose', default='0.0')
36+
37+
world = os.path.join(
38+
get_package_share_directory('turtlebot3_gazebo'),
39+
'worlds',
40+
'turtlebot3_dqn_stage1.world'
41+
)
42+
set_env_vars_resources = AppendEnvironmentVariable(
43+
'GZ_SIM_RESOURCE_PATH',
44+
os.path.join(
45+
get_package_share_directory('turtlebot3_gazebo'),
46+
'models'
47+
)
48+
)
49+
50+
gzserver_cmd = IncludeLaunchDescription(
51+
PythonLaunchDescriptionSource(
52+
os.path.join(ros_gz_sim, 'launch', 'gz_sim.launch.py')
53+
),
54+
launch_arguments={'gz_args': ['-r -s -v4 ', world]}.items()
55+
)
56+
gzclient_cmd = IncludeLaunchDescription(
57+
PythonLaunchDescriptionSource(
58+
os.path.join(ros_gz_sim, 'launch', 'gz_sim.launch.py')
59+
),
60+
launch_arguments={'gz_args': '-g -v4 '}.items()
61+
)
62+
63+
robot_state_publisher_cmd = IncludeLaunchDescription(
64+
PythonLaunchDescriptionSource(
65+
os.path.join(launch_file_dir, 'robot_state_publisher.launch.py')
66+
),
67+
launch_arguments={'use_sim_time': use_sim_time}.items()
68+
)
69+
70+
spawn_turtlebot_cmd = IncludeLaunchDescription(
71+
PythonLaunchDescriptionSource(
72+
os.path.join(launch_file_dir, 'spawn_turtlebot3.launch.py')
73+
),
74+
launch_arguments={
75+
'x_pose': x_pose,
76+
'y_pose': y_pose
77+
}.items()
78+
)
79+
80+
bridge_node = Node(
81+
package='ros_gz_bridge',
82+
executable='parameter_bridge',
83+
name='parameter_bridge_services',
84+
arguments=[
85+
'/delete_entity@ros_gz_interfaces/srv/DeleteEntity',
86+
'/spawn_entity@ros_gz_interfaces/srv/SpawnEntity',
87+
'/reset_simulation@std_srvs/srv/Empty'
88+
],
89+
output='screen'
90+
)
91+
92+
ld = LaunchDescription()
93+
94+
ld.add_action(set_env_vars_resources)
95+
ld.add_action(gzserver_cmd)
96+
ld.add_action(gzclient_cmd)
97+
ld.add_action(robot_state_publisher_cmd)
98+
ld.add_action(spawn_turtlebot_cmd)
99+
ld.add_action(bridge_node)
100+
101+
return ld

0 commit comments

Comments
 (0)