-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathavatar_02_mapping.launch.py
118 lines (104 loc) · 4.14 KB
/
avatar_02_mapping.launch.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
from launch import LaunchDescription
from launch_ros.actions import Node
# For environment variables
from launch.actions import SetEnvironmentVariable
# Import other 'launch files'
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
import os
from ament_index_python import get_package_share_directory
from datetime import datetime
def generate_launch_description():
ld = LaunchDescription()
# Set ROS Domain ID
# ld.add_action(SetEnvironmentVariable('ROS_DOMAIN_ID', '101'))
# TF
tf2_ros = Node(
package='tf2_ros',
executable='static_transform_publisher',
arguments=['0', '0', '0', '0', '0', '0', 'map', 'odom'],
name='odom_to_odom'
)
odom_to_base_link = Node(
package='tf2_ros',
executable='static_transform_publisher',
arguments=['--x', '0', '--y', '0', '--z', '0', '--yaw', '0', '--pitch', '0', '--roll', '0',
'--frame-id','odom','--child-frame-id','base_link'],
name='odom_to_base_link'
)
base_link_to_camera_link = Node(
package='tf2_ros',
executable='static_transform_publisher',
arguments = ['--x', '0', '--y', '0', '--z', '0', '--yaw', '-1.5708', '--pitch', '0', '--roll', '-1.5708',
'--frame-id','base_link','--child-frame-id','camera_frame'],
name='base_link_to_camera_link'
)
# ros2 run stella_vslam_ros run_slam -v ./orb_vocab.fbow -c ./runcam_720p.yaml --map-db-out ./runcam_720_0420.msg
# stella_ros = Node(
# package='stella_vslam_ros',
# executable='run_slam',
# name='stella_ros',
# output="screen",
# remappings=[("/stella_ros/camera_pose","/mavros/odometry/out")],
# #("/camera/image_raw", "/cam0/image_raw")]
# arguments=["-v","./orb_vocab.fbow","-c","./runcam_720p.yaml",
# "--map-db-out","./runcam_720_0420.msg"
# #"--ros-args","-p","publish_tf:=false"
# ]
#)
# Generate the timestamp string
timestamp = datetime.now().strftime("%Y%m%d-%H%M")
# Create the modified argument
map_argument = "../data/map/avatar720-" + timestamp + ".msg"
# Update the arguments list for the stella_ros node
stella_ros_arguments = [
"-v", "./orb_vocab.fbow",
"-c", "./avatar_720p.yaml",
"--map-db-out", map_argument
]
stella_ros = Node(
package='stella_vslam_ros',
executable='run_slam',
name='stella_ros',
output="screen",
# remappings=[("/stella_ros/camera_pose","/mavros/vision_pose/pose")],
# remappings=[("/stella_ros/camera_pose","/mavros/odometry/out")],
#arguments=["-v","./orb_vocab.fbow","-c","./runcam_720p.yaml","--map-db-out","./runcam_720_0420.msg"],
arguments=stella_ros_arguments,
parameters=[
{"odom_frame": "odom"},
{"map_frame": "map"},
{"base_link": "base_link"},
{"camera_frame": "camera_frame"},
{"publish_tf": True},
{"publish_keyframes": True},
{"transform_tolerance": 0.5}
]
)
#ros2 run micro_ros_agent micro_ros_agent udp4 --port 8888 ROS_DOMAIN_ID=0
# micro_ros = Node(
# package='micro_ros_agent',
# executable='micro_ros_agent',
# name='micro_ros',
# arguments=["udp4","--port","8888","ROS_DOMAIN_ID=0"]
# )
# #ros2 run ros_gz_image image_bridge /camera
# ros_gz_camera_bridge = Node(
# package='ros_gz_image',
# executable='image_bridge',
# name='camera_bridge',
# arguments=["/camera"]
# )
# #ros2 run px4_ros_com offboard_control
# px4_offboard = Node(
# package='px4_ros_com',
# executable='offboard_control',
# name='offboard_takeoff'
# )
ld.add_action(stella_ros)
#ld.add_action(tf2_ros)
ld.add_action(odom_to_base_link)
ld.add_action(base_link_to_camera_link)
#ld.add_action(ros_gz_camera_bridge)
# ld.add_action(px4_offboard)
return ld