mirror of
https://git.ti.com/git/mmwave_radar/mmwave_ti_ros.git
synced 2026-05-21 01:12:08 +00:00
[ros2_driver] Following updates made to ros2_driver/src/ti_mmwave_rospkg:
1. Updated CMakeLists.txt to install the "cfg" folder. 2. Path to .cfg file is now set using get_package_share_directory(). 3. Updated 6843*.py launch files to add a feature optionally disable rViz with an launch argument "rviz". To disable rViz, pass "rviz:=false" in the launch command.
This commit is contained in:
@@ -224,6 +224,10 @@ install(DIRECTORY
|
||||
config
|
||||
DESTINATION share/${PROJECT_NAME}
|
||||
)
|
||||
install(DIRECTORY
|
||||
cfg
|
||||
DESTINATION share/${PROJECT_NAME}
|
||||
)
|
||||
install(TARGETS
|
||||
mmWaveCommSrv
|
||||
DESTINATION lib/${PROJECT_NAME}
|
||||
|
||||
@@ -8,14 +8,14 @@ from ament_index_python.packages import get_package_share_directory
|
||||
def generate_launch_description():
|
||||
|
||||
# Enter Path and Name Here
|
||||
path = "/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/cfg/1443_Standard.cfg";
|
||||
my_package_dir = get_package_share_directory('ti_mmwave_rospkg')
|
||||
path = os.path.join(my_package_dir,'cfg','1443_Standard.cfg')
|
||||
device = "1443"
|
||||
name = "/mmWaveCLI"
|
||||
command_port = "/dev/ttyUSB0"
|
||||
command_rate = "115200"
|
||||
data_port = "/dev/ttyUSB1"
|
||||
data_rate = "921600"
|
||||
my_package_dir = get_package_share_directory('ti_mmwave_rospkg')
|
||||
|
||||
ld = LaunchDescription()
|
||||
ConfigParameters = os.path.join(
|
||||
@@ -93,7 +93,6 @@ def generate_launch_description():
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
arguments=['-d', os.path.join(my_package_dir, 'launch', 'rviz.rviz')]
|
||||
|
||||
)
|
||||
|
||||
ld.add_action(global_param_node)
|
||||
|
||||
@@ -8,14 +8,14 @@ from ament_index_python.packages import get_package_share_directory
|
||||
def generate_launch_description():
|
||||
|
||||
# Enter Path and Name Here
|
||||
path = "/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/cfg/1642_Standard.cfg";
|
||||
my_package_dir = get_package_share_directory('ti_mmwave_rospkg')
|
||||
path = os.path.join(my_package_dir,'cfg','1642_Standard.cfg')
|
||||
name = "/mmWaveCLI"
|
||||
device = "1642"
|
||||
command_port = "/dev/ttyUSB0"
|
||||
command_rate = "115200"
|
||||
data_port = "/dev/ttyUSB1"
|
||||
data_rate = "921600"
|
||||
my_package_dir = get_package_share_directory('ti_mmwave_rospkg')
|
||||
|
||||
ld = LaunchDescription()
|
||||
ConfigParameters = os.path.join(
|
||||
@@ -93,7 +93,6 @@ def generate_launch_description():
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
arguments=['-d', os.path.join(my_package_dir, 'launch', 'rviz.rviz')]
|
||||
|
||||
)
|
||||
|
||||
ld.add_action(global_param_node)
|
||||
|
||||
@@ -8,14 +8,14 @@ from ament_index_python.packages import get_package_share_directory
|
||||
def generate_launch_description():
|
||||
|
||||
# Enter Path and Name Here
|
||||
path = "/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/cfg/1843_Standard.cfg";
|
||||
my_package_dir = get_package_share_directory('ti_mmwave_rospkg')
|
||||
path = os.path.join(my_package_dir,'cfg','1843_Standard.cfg')
|
||||
device = "1843"
|
||||
name = "/mmWaveCLI"
|
||||
command_port = "/dev/ttyUSB0"
|
||||
command_rate = "115200"
|
||||
data_port = "/dev/ttyUSB1"
|
||||
data_rate = "921600"
|
||||
my_package_dir = get_package_share_directory('ti_mmwave_rospkg')
|
||||
|
||||
ld = LaunchDescription()
|
||||
ConfigParameters = os.path.join(
|
||||
@@ -93,7 +93,6 @@ def generate_launch_description():
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
arguments=['-d', os.path.join(my_package_dir, 'launch', 'rviz.rviz')]
|
||||
|
||||
)
|
||||
|
||||
ld.add_action(global_param_node)
|
||||
|
||||
@@ -11,14 +11,14 @@ from ament_index_python.packages import get_package_share_directory
|
||||
|
||||
def generate_launch_description():
|
||||
|
||||
path = "/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/cfg/6432_Standard_Uncompressed.cfg";
|
||||
my_package_dir = get_package_share_directory('ti_mmwave_rospkg')
|
||||
path = os.path.join(my_package_dir,'cfg','6432_Standard_Uncompressed.cfg')
|
||||
device = "6432"
|
||||
name = "/mmWaveCLI"
|
||||
command_port = "/dev/ttyACM0"
|
||||
command_rate = "115200"
|
||||
data_port = "/dev/ttyACM0"
|
||||
data_rate = "115200"
|
||||
my_package_dir = get_package_share_directory('ti_mmwave_rospkg')
|
||||
|
||||
ld = LaunchDescription()
|
||||
ConfigParameters = os.path.join(
|
||||
|
||||
@@ -1,23 +1,32 @@
|
||||
import os
|
||||
from launch import LaunchDescription
|
||||
from launch.substitutions import PathJoinSubstitution
|
||||
from launch import LaunchDescription, conditions
|
||||
from launch.actions import DeclareLaunchArgument
|
||||
from launch.substitutions import LaunchConfiguration
|
||||
from launch_ros.actions import Node
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
|
||||
def generate_launch_description():
|
||||
|
||||
# Declare the launch argument
|
||||
rviz_arg = DeclareLaunchArgument(
|
||||
'rviz',
|
||||
default_value='true',
|
||||
description='Enable RViz'
|
||||
)
|
||||
|
||||
# Use the launch argument in the condition for adding the RViz node
|
||||
rviz_enabled = LaunchConfiguration('rviz')
|
||||
|
||||
# Enter Path and Name Here
|
||||
path = "/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/cfg/6843AOP_Standard.cfg";
|
||||
my_package_dir = get_package_share_directory('ti_mmwave_rospkg')
|
||||
path = os.path.join(my_package_dir,'cfg','6843AOP_Standard.cfg')
|
||||
device = "6843"
|
||||
name = "/mmWaveCLI"
|
||||
command_port = "/dev/ttyUSB0"
|
||||
command_rate = "115200"
|
||||
data_port = "/dev/ttyUSB1"
|
||||
data_rate = "921600"
|
||||
my_package_dir = get_package_share_directory('ti_mmwave_rospkg')
|
||||
|
||||
ld = LaunchDescription()
|
||||
ConfigParameters = os.path.join(
|
||||
my_package_dir,
|
||||
'config',
|
||||
@@ -89,13 +98,16 @@ def generate_launch_description():
|
||||
]
|
||||
|
||||
)
|
||||
|
||||
Rviz2 = Node(
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
arguments=['-d', os.path.join(my_package_dir, 'launch', 'rviz.rviz')]
|
||||
|
||||
arguments=['-d', os.path.join(my_package_dir, 'launch', 'rviz.rviz')],
|
||||
condition=conditions.IfCondition(rviz_enabled) # only launch RViz if the argument is true
|
||||
)
|
||||
|
||||
ld = LaunchDescription()
|
||||
ld.add_action(rviz_arg)
|
||||
ld.add_action(global_param_node)
|
||||
ld.add_action(mmWaveCommSrv)
|
||||
ld.add_action(mmWaveQuickConfig)
|
||||
|
||||
@@ -1,23 +1,32 @@
|
||||
import os
|
||||
from launch import LaunchDescription
|
||||
from launch.substitutions import PathJoinSubstitution
|
||||
from launch import LaunchDescription, conditions
|
||||
from launch.actions import DeclareLaunchArgument
|
||||
from launch.substitutions import LaunchConfiguration
|
||||
from launch_ros.actions import Node
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
|
||||
def generate_launch_description():
|
||||
|
||||
# Declare the launch argument
|
||||
rviz_arg = DeclareLaunchArgument(
|
||||
'rviz',
|
||||
default_value='true',
|
||||
description='Enable RViz'
|
||||
)
|
||||
|
||||
# Use the launch argument in the condition for adding the RViz node
|
||||
rviz_enabled = LaunchConfiguration('rviz')
|
||||
|
||||
# Enter Path and Name Here
|
||||
path = "/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/cfg/6843AOP_Tracking.cfg";
|
||||
my_package_dir = get_package_share_directory('ti_mmwave_rospkg')
|
||||
path = os.path.join(my_package_dir,'cfg','6843AOP_Tracking.cfg')
|
||||
device = "6843"
|
||||
name = "/mmWaveCLI"
|
||||
command_port = "/dev/ttyUSB0"
|
||||
command_rate = "115200"
|
||||
data_port = "/dev/ttyUSB1"
|
||||
data_rate = "921600"
|
||||
my_package_dir = get_package_share_directory('ti_mmwave_rospkg')
|
||||
|
||||
ld = LaunchDescription()
|
||||
ConfigParameters = os.path.join(
|
||||
my_package_dir,
|
||||
'config',
|
||||
@@ -89,13 +98,16 @@ def generate_launch_description():
|
||||
]
|
||||
|
||||
)
|
||||
|
||||
Rviz2 = Node(
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
arguments=['-d', os.path.join(my_package_dir, 'launch', 'rviz.rviz')]
|
||||
|
||||
arguments=['-d', os.path.join(my_package_dir, 'launch', 'rviz.rviz')],
|
||||
condition=conditions.IfCondition(rviz_enabled) # only launch RViz if the argument is true
|
||||
)
|
||||
|
||||
ld = LaunchDescription()
|
||||
ld.add_action(rviz_arg)
|
||||
ld.add_action(global_param_node)
|
||||
ld.add_action(mmWaveCommSrv)
|
||||
ld.add_action(mmWaveQuickConfig)
|
||||
|
||||
@@ -1,23 +1,32 @@
|
||||
import os
|
||||
from launch import LaunchDescription
|
||||
from launch.substitutions import PathJoinSubstitution
|
||||
from launch import LaunchDescription, conditions
|
||||
from launch.actions import DeclareLaunchArgument
|
||||
from launch.substitutions import LaunchConfiguration
|
||||
from launch_ros.actions import Node
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
|
||||
def generate_launch_description():
|
||||
|
||||
# Declare the launch argument
|
||||
rviz_arg = DeclareLaunchArgument(
|
||||
'rviz',
|
||||
default_value='true',
|
||||
description='Enable RViz'
|
||||
)
|
||||
|
||||
# Use the launch argument in the condition for adding the RViz node
|
||||
rviz_enabled = LaunchConfiguration('rviz')
|
||||
|
||||
# Enter Path and Name Here
|
||||
path = "/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/cfg/6843ISK_Occupancy.cfg";
|
||||
my_package_dir = get_package_share_directory('ti_mmwave_rospkg')
|
||||
path = os.path.join(my_package_dir,'cfg','6843ISK_Occupancy.cfg')
|
||||
device = "6843"
|
||||
name = "/mmWaveCLI"
|
||||
command_port = "/dev/ttyUSB0"
|
||||
command_rate = "115200"
|
||||
data_port = "/dev/ttyUSB1"
|
||||
data_rate = "921600"
|
||||
my_package_dir = get_package_share_directory('ti_mmwave_rospkg')
|
||||
|
||||
ld = LaunchDescription()
|
||||
ConfigParameters = os.path.join(
|
||||
my_package_dir,
|
||||
'config',
|
||||
@@ -89,13 +98,16 @@ def generate_launch_description():
|
||||
]
|
||||
|
||||
)
|
||||
|
||||
Rviz2 = Node(
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
arguments=['-d', os.path.join(my_package_dir, 'launch', 'rviz.rviz')]
|
||||
|
||||
arguments=['-d', os.path.join(my_package_dir, 'launch', 'rviz.rviz')],
|
||||
condition=conditions.IfCondition(rviz_enabled) # only launch RViz if the argument is true
|
||||
)
|
||||
|
||||
ld = LaunchDescription()
|
||||
ld.add_action(rviz_arg)
|
||||
ld.add_action(global_param_node)
|
||||
ld.add_action(mmWaveCommSrv)
|
||||
ld.add_action(mmWaveQuickConfig)
|
||||
|
||||
@@ -1,23 +1,32 @@
|
||||
import os
|
||||
from launch import LaunchDescription
|
||||
from launch.substitutions import PathJoinSubstitution
|
||||
from launch import LaunchDescription, conditions
|
||||
from launch.actions import DeclareLaunchArgument
|
||||
from launch.substitutions import LaunchConfiguration
|
||||
from launch_ros.actions import Node
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
|
||||
def generate_launch_description():
|
||||
|
||||
# Declare the launch argument
|
||||
rviz_arg = DeclareLaunchArgument(
|
||||
'rviz',
|
||||
default_value='true',
|
||||
description='Enable RViz'
|
||||
)
|
||||
|
||||
# Use the launch argument in the condition for adding the RViz node
|
||||
rviz_enabled = LaunchConfiguration('rviz')
|
||||
|
||||
# Enter Path and Name Here
|
||||
path = "/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/cfg/6843ISK_Standard.cfg";
|
||||
my_package_dir = get_package_share_directory('ti_mmwave_rospkg')
|
||||
path = os.path.join(my_package_dir,'cfg','6843ISK_Standard.cfg')
|
||||
device = "6843"
|
||||
name = "/mmWaveCLI"
|
||||
command_port = "/dev/ttyUSB0"
|
||||
command_rate = "115200"
|
||||
data_port = "/dev/ttyUSB1"
|
||||
data_rate = "921600"
|
||||
my_package_dir = get_package_share_directory('ti_mmwave_rospkg')
|
||||
|
||||
ld = LaunchDescription()
|
||||
ConfigParameters = os.path.join(
|
||||
my_package_dir,
|
||||
'config',
|
||||
@@ -89,13 +98,16 @@ def generate_launch_description():
|
||||
]
|
||||
|
||||
)
|
||||
|
||||
Rviz2 = Node(
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
arguments=['-d', os.path.join(my_package_dir, 'launch', 'rviz.rviz')]
|
||||
|
||||
arguments=['-d', os.path.join(my_package_dir, 'launch', 'rviz.rviz')],
|
||||
condition=conditions.IfCondition(rviz_enabled) # only launch RViz if the argument is true
|
||||
)
|
||||
|
||||
ld = LaunchDescription()
|
||||
ld.add_action(rviz_arg)
|
||||
ld.add_action(global_param_node)
|
||||
ld.add_action(mmWaveCommSrv)
|
||||
ld.add_action(mmWaveQuickConfig)
|
||||
|
||||
@@ -1,23 +1,32 @@
|
||||
import os
|
||||
from launch import LaunchDescription
|
||||
from launch.substitutions import PathJoinSubstitution
|
||||
from launch import LaunchDescription, conditions
|
||||
from launch.actions import DeclareLaunchArgument
|
||||
from launch.substitutions import LaunchConfiguration
|
||||
from launch_ros.actions import Node
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
|
||||
def generate_launch_description():
|
||||
|
||||
# Declare the launch argument
|
||||
rviz_arg = DeclareLaunchArgument(
|
||||
'rviz',
|
||||
default_value='true',
|
||||
description='Enable RViz'
|
||||
)
|
||||
|
||||
# Use the launch argument in the condition for adding the RViz node
|
||||
rviz_enabled = LaunchConfiguration('rviz')
|
||||
|
||||
# Enter Path and Name Here
|
||||
path = "/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/cfg/6843AOP_Tracking.cfg";
|
||||
my_package_dir = get_package_share_directory('ti_mmwave_rospkg')
|
||||
path = os.path.join(my_package_dir,'cfg','6843AOP_Tracking.cfg')
|
||||
device = "6843"
|
||||
name = "/mmWaveCLI"
|
||||
command_port = "/dev/ttyUSB0"
|
||||
command_rate = "115200"
|
||||
data_port = "/dev/ttyUSB1"
|
||||
data_rate = "921600"
|
||||
my_package_dir = get_package_share_directory('ti_mmwave_rospkg')
|
||||
|
||||
ld = LaunchDescription()
|
||||
ConfigParameters = os.path.join(
|
||||
my_package_dir,
|
||||
'config',
|
||||
@@ -89,13 +98,16 @@ def generate_launch_description():
|
||||
]
|
||||
|
||||
)
|
||||
|
||||
Rviz2 = Node(
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
arguments=['-d', os.path.join(my_package_dir, 'launch', 'rviz.rviz')]
|
||||
|
||||
arguments=['-d', os.path.join(my_package_dir, 'launch', 'rviz.rviz')],
|
||||
condition=conditions.IfCondition(rviz_enabled) # only launch RViz if the argument is true
|
||||
)
|
||||
|
||||
ld = LaunchDescription()
|
||||
ld.add_action(rviz_arg)
|
||||
ld.add_action(global_param_node)
|
||||
ld.add_action(mmWaveCommSrv)
|
||||
ld.add_action(mmWaveQuickConfig)
|
||||
|
||||
21
ros2_driver/src/ti_mmwave_rospkg/launch/rviz_launch.py
Normal file
21
ros2_driver/src/ti_mmwave_rospkg/launch/rviz_launch.py
Normal file
@@ -0,0 +1,21 @@
|
||||
import os
|
||||
from launch import LaunchDescription
|
||||
from launch_ros.actions import Node
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
|
||||
def generate_launch_description():
|
||||
|
||||
# Enter Path and Name Here
|
||||
my_package_dir = get_package_share_directory('ti_mmwave_rospkg')
|
||||
|
||||
Rviz2 = Node(
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
arguments=['-d', os.path.join(my_package_dir, 'launch', 'rviz.rviz')]
|
||||
)
|
||||
|
||||
ld = LaunchDescription([
|
||||
Rviz2
|
||||
])
|
||||
|
||||
return ld
|
||||
Reference in New Issue
Block a user