mirror of
https://git.ti.com/git/mmwave_radar/mmwave_ti_ros.git
synced 2026-05-21 01:12:08 +00:00
Pull request #11: ROS2 update for Processor's Robotics SDK
Merge in MITL/mmwave_ti_ros from ros2_update_robotics_sdk to master
* commit 'be917505ac457309c8b85002cf3384fabc6cb1b2':
[ros2_driver/ti_mmwave_rospkg] Updated the launch files and the rviz file. - Added a common launch file IWR6843.py for all the IWR6843x launch files. - CLI config file, command port, and data port can passed at the command line with launch arguments. For example, below is equivalent to '6843ISK_Tracking.py': ros2 launch ti_mmwave_rospkg IWR6843.py cfg_file:=6843ISK_Tracking.cfg - 6843{ISK,AOP}_{Standard,Tracking,Occupancy}.py now call the common launch file. - Updated the rviz file to display the XYZ axes.
[ros2_driver/ti_mmwave_rospkg_msgs] Updated to use the standard header message, std_msgs/Header. Note that "seq" field in the header was deprecated in ROS 2.
[ros2_driver] Removed ti_mmwave_rospkg/src/{build, install, log} folders.
This commit is contained in:
@@ -26,8 +26,8 @@
|
||||
#define COUNT_SYNC_MAX 2
|
||||
|
||||
|
||||
class DataUARTHandlerNode : public rclcpp::Node
|
||||
{
|
||||
class DataUARTHandlerNode : public rclcpp::Node
|
||||
{
|
||||
public:
|
||||
explicit DataUARTHandlerNode();
|
||||
|
||||
@@ -39,40 +39,40 @@ private:
|
||||
|
||||
class DataUARTHandler
|
||||
{
|
||||
|
||||
|
||||
public:
|
||||
|
||||
|
||||
//DataUARTHandler();
|
||||
|
||||
DataUARTHandler(std::shared_ptr<rclcpp::Node> nh);
|
||||
|
||||
|
||||
void setFrameID(char const* myFrameID);
|
||||
|
||||
/*User callable function to set the UARTPort*/
|
||||
void setUARTPort(char const* mySerialPort);
|
||||
|
||||
|
||||
/*User callable function to set the BaudRate*/
|
||||
void setBaudRate(int myBaudRate);
|
||||
|
||||
/*User callable function to set maxAllowedElevationAngleDeg*/
|
||||
void setMaxAllowedElevationAngleDeg(int myMaxAllowedElevationAngleDeg);
|
||||
|
||||
|
||||
/*User callable function to set maxAllowedElevationAngleDeg*/
|
||||
void setMaxAllowedAzimuthAngleDeg(int myMaxAllowedAzimuthAngleDeg);
|
||||
|
||||
void setNodeHandle(std::shared_ptr<rclcpp::Node> nh);
|
||||
|
||||
// void setNodeHandle(std::shared_ptr<rclcpp::Node> nh);
|
||||
|
||||
/*User callable function to start the handler's internal threads*/
|
||||
void start(void);
|
||||
|
||||
|
||||
/*User callable function to stop the handler's internal threads*/
|
||||
void stop();
|
||||
|
||||
/*Helper functions to allow pthread compatability*/
|
||||
static void* readIncomingData_helper(void *context);
|
||||
|
||||
|
||||
static void* sortIncomingData_helper(void *context);
|
||||
|
||||
|
||||
static void* syncedBufferSwap_helper(void *context);
|
||||
|
||||
/* Function to handle signals such as SIGINT */
|
||||
@@ -81,7 +81,7 @@ public:
|
||||
/*Sorted mmwDemo Data structure*/
|
||||
mmwDataPacket mmwData;
|
||||
|
||||
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr DataUARTHandler_pub;
|
||||
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr radar_scan_pcl_pub;
|
||||
rclcpp::Publisher<ti_mmwave_rospkg_msgs::msg::RadarScan>::SharedPtr radar_scan_pub;
|
||||
rclcpp::Publisher<ti_mmwave_rospkg_msgs::msg::RadarOccupancy>::SharedPtr radar_occupancy_pub;
|
||||
rclcpp::Publisher<ti_mmwave_rospkg_msgs::msg::RadarPointTrackID>::SharedPtr radar_trackid_pub;
|
||||
@@ -112,64 +112,64 @@ private:
|
||||
char const* frameID;
|
||||
/*Contains the name of the serial port*/
|
||||
char const* dataSerialPort;
|
||||
|
||||
|
||||
/*Contains the baud Rate*/
|
||||
int dataBaudRate;
|
||||
|
||||
/*Contains the max_allowed_elevation_angle_deg (points with elevation angles
|
||||
|
||||
/*Contains the max_allowed_elevation_angle_deg (points with elevation angles
|
||||
outside +/- max_allowed_elevation_angle_deg will be removed)*/
|
||||
int maxAllowedElevationAngleDeg;
|
||||
|
||||
/*Contains the max_allowed_azimuth_angle_deg (points with azimuth angles
|
||||
|
||||
/*Contains the max_allowed_azimuth_angle_deg (points with azimuth angles
|
||||
outside +/- max_allowed_azimuth_angle_deg will be removed)*/
|
||||
int maxAllowedAzimuthAngleDeg;
|
||||
|
||||
|
||||
/*Mutex protected variable which synchronizes threads*/
|
||||
int countSync;
|
||||
|
||||
/*Boolean used to notify threads to exit*/
|
||||
bool stop_threads;
|
||||
|
||||
|
||||
/*Read/Write Buffers*/
|
||||
std::vector<uint8_t> pingPongBuffers[2];
|
||||
|
||||
|
||||
/*Pointer to current data (sort)*/
|
||||
std::vector<uint8_t>* currentBufp;
|
||||
|
||||
|
||||
/*Pointer to new data (read)*/
|
||||
std::vector<uint8_t>* nextBufp;
|
||||
|
||||
|
||||
/*Mutex protecting the countSync variable */
|
||||
pthread_mutex_t countSync_mutex;
|
||||
|
||||
|
||||
/*Mutex protecting the nextBufp pointer*/
|
||||
pthread_mutex_t nextBufp_mutex;
|
||||
|
||||
|
||||
/*Mutex protecting the currentBufp pointer*/
|
||||
pthread_mutex_t currentBufp_mutex;
|
||||
|
||||
|
||||
/*Condition variable which blocks the Swap Thread until signaled*/
|
||||
pthread_cond_t countSync_max_cv;
|
||||
|
||||
|
||||
/*Condition variable which blocks the Read Thread until signaled*/
|
||||
pthread_cond_t read_go_cv;
|
||||
|
||||
|
||||
/*Condition variable which blocks the Sort Thread until signaled*/
|
||||
pthread_cond_t sort_go_cv;
|
||||
|
||||
|
||||
/*Swap Buffer Pointers Thread*/
|
||||
void *syncedBufferSwap(void);
|
||||
|
||||
|
||||
/*Checks if the magic word was found*/
|
||||
int isMagicWord(uint8_t last8Bytes[8]);
|
||||
|
||||
|
||||
/*Read incoming UART Data Thread*/
|
||||
void *readIncomingData(void);
|
||||
|
||||
|
||||
/*Sort incoming UART Data Thread*/
|
||||
void *sortIncomingData(void);
|
||||
|
||||
|
||||
rclcpp::Node::SharedPtr nodeHandle;
|
||||
};
|
||||
|
||||
#endif
|
||||
#endif
|
||||
|
||||
@@ -1,118 +1,29 @@
|
||||
import os
|
||||
from launch import LaunchDescription, conditions
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import DeclareLaunchArgument
|
||||
from launch.actions import IncludeLaunchDescription
|
||||
from launch.substitutions import LaunchConfiguration
|
||||
from launch_ros.actions import Node
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
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'
|
||||
)
|
||||
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
|
||||
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"
|
||||
|
||||
ConfigParameters = os.path.join(
|
||||
my_package_dir,
|
||||
'config',
|
||||
'global_params.yaml',
|
||||
'launch/*.rviz'
|
||||
)
|
||||
global_param_node = Node(
|
||||
package='ti_mmwave_rospkg',
|
||||
executable='ConfigParameterServer',
|
||||
name='ConfigParameterServer',
|
||||
parameters=[ConfigParameters]
|
||||
)
|
||||
|
||||
mmWaveCommSrv = Node(
|
||||
package="ti_mmwave_rospkg",
|
||||
executable="mmWaveCommSrv",
|
||||
name="mmWaveCommSrv",
|
||||
output="screen",
|
||||
emulate_tty=True,
|
||||
parameters=[
|
||||
{"command_port": command_port},
|
||||
{"command_rate": command_rate},
|
||||
{"data_port": data_port},
|
||||
{"data_rate": data_rate},
|
||||
{"max_allowed_elevation_angle_deg": "90"},
|
||||
{"max_allowed_azimuth_angle_deg": "90"},
|
||||
{"frame_id": "/ti_mmwave_0"},
|
||||
{"mmwavecli_name": name},
|
||||
{"mmwavecli_cfg": path}
|
||||
]
|
||||
)
|
||||
|
||||
mmWaveQuickConfig = Node(
|
||||
package="ti_mmwave_rospkg",
|
||||
executable="mmWaveQuickConfig",
|
||||
name="mmWaveQuickConfig",
|
||||
output="screen",
|
||||
emulate_tty=True,
|
||||
parameters=[
|
||||
{"mmwavecli_name": name},
|
||||
{"mmwavecli_cfg": path}
|
||||
]
|
||||
)
|
||||
|
||||
ParameterParser = Node(
|
||||
package="ti_mmwave_rospkg",
|
||||
executable="ParameterParser",
|
||||
name="ParameterParser",
|
||||
output="screen",
|
||||
emulate_tty=True,
|
||||
parameters=[
|
||||
{"device_name": device},
|
||||
{"mmwavecli_name": name},
|
||||
{"mmwavecli_cfg": path}
|
||||
]
|
||||
)
|
||||
|
||||
DataHandlerClass = Node(
|
||||
package="ti_mmwave_rospkg",
|
||||
executable="DataHandlerClass",
|
||||
name="DataHandlerClass",
|
||||
output="screen",
|
||||
emulate_tty=True,
|
||||
parameters=[
|
||||
{"mmwavecli_name": name},
|
||||
{"mmwavecli_cfg": path},
|
||||
{"data_port": data_port},
|
||||
{"data_rate": data_rate}
|
||||
]
|
||||
|
||||
)
|
||||
|
||||
Rviz2 = Node(
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
arguments=['-d', os.path.join(my_package_dir, 'launch', 'rviz.rviz')],
|
||||
condition=conditions.IfCondition(rviz_enabled) # only launch RViz if the argument is true
|
||||
# include IWR6843.py
|
||||
package_dir = get_package_share_directory('ti_mmwave_rospkg')
|
||||
iwr6843_include = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(os.path.join(package_dir,'launch','IWR6843.py')),
|
||||
launch_arguments={
|
||||
"cfg_file": '6843AOP_Standard.cfg',
|
||||
"command_port": "/dev/ttyUSB0",
|
||||
"data_port": "/dev/ttyUSB1",
|
||||
"rviz": LaunchConfiguration('rviz'),
|
||||
}.items()
|
||||
)
|
||||
|
||||
ld = LaunchDescription()
|
||||
ld.add_action(rviz_arg)
|
||||
ld.add_action(global_param_node)
|
||||
ld.add_action(mmWaveCommSrv)
|
||||
ld.add_action(mmWaveQuickConfig)
|
||||
ld.add_action(ParameterParser)
|
||||
ld.add_action(DataHandlerClass)
|
||||
ld.add_action(Rviz2)
|
||||
ld.add_action(iwr6843_include)
|
||||
|
||||
return ld
|
||||
|
||||
@@ -1,118 +1,29 @@
|
||||
import os
|
||||
from launch import LaunchDescription, conditions
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import DeclareLaunchArgument
|
||||
from launch.actions import IncludeLaunchDescription
|
||||
from launch.substitutions import LaunchConfiguration
|
||||
from launch_ros.actions import Node
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
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'
|
||||
)
|
||||
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
|
||||
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"
|
||||
|
||||
ConfigParameters = os.path.join(
|
||||
my_package_dir,
|
||||
'config',
|
||||
'global_params.yaml',
|
||||
'launch/*.rviz'
|
||||
)
|
||||
global_param_node = Node(
|
||||
package='ti_mmwave_rospkg',
|
||||
executable='ConfigParameterServer',
|
||||
name='ConfigParameterServer',
|
||||
parameters=[ConfigParameters]
|
||||
)
|
||||
|
||||
mmWaveCommSrv = Node(
|
||||
package="ti_mmwave_rospkg",
|
||||
executable="mmWaveCommSrv",
|
||||
name="mmWaveCommSrv",
|
||||
output="screen",
|
||||
emulate_tty=True,
|
||||
parameters=[
|
||||
{"command_port": command_port},
|
||||
{"command_rate": command_rate},
|
||||
{"data_port": data_port},
|
||||
{"data_rate": data_rate},
|
||||
{"max_allowed_elevation_angle_deg": "90"},
|
||||
{"max_allowed_azimuth_angle_deg": "90"},
|
||||
{"frame_id": "/ti_mmwave_0"},
|
||||
{"mmwavecli_name": name},
|
||||
{"mmwavecli_cfg": path}
|
||||
]
|
||||
)
|
||||
|
||||
mmWaveQuickConfig = Node(
|
||||
package="ti_mmwave_rospkg",
|
||||
executable="mmWaveQuickConfig",
|
||||
name="mmWaveQuickConfig",
|
||||
output="screen",
|
||||
emulate_tty=True,
|
||||
parameters=[
|
||||
{"mmwavecli_name": name},
|
||||
{"mmwavecli_cfg": path}
|
||||
]
|
||||
)
|
||||
|
||||
ParameterParser = Node(
|
||||
package="ti_mmwave_rospkg",
|
||||
executable="ParameterParser",
|
||||
name="ParameterParser",
|
||||
output="screen",
|
||||
emulate_tty=True,
|
||||
parameters=[
|
||||
{"device_name": device},
|
||||
{"mmwavecli_name": name},
|
||||
{"mmwavecli_cfg": path}
|
||||
]
|
||||
)
|
||||
|
||||
DataHandlerClass = Node(
|
||||
package="ti_mmwave_rospkg",
|
||||
executable="DataHandlerClass",
|
||||
name="DataHandlerClass",
|
||||
output="screen",
|
||||
emulate_tty=True,
|
||||
parameters=[
|
||||
{"mmwavecli_name": name},
|
||||
{"mmwavecli_cfg": path},
|
||||
{"data_port": data_port},
|
||||
{"data_rate": data_rate}
|
||||
]
|
||||
|
||||
)
|
||||
|
||||
Rviz2 = Node(
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
arguments=['-d', os.path.join(my_package_dir, 'launch', 'rviz.rviz')],
|
||||
condition=conditions.IfCondition(rviz_enabled) # only launch RViz if the argument is true
|
||||
# include IWR6843.py
|
||||
package_dir = get_package_share_directory('ti_mmwave_rospkg')
|
||||
iwr6843_include = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(os.path.join(package_dir,'launch','IWR6843.py')),
|
||||
launch_arguments={
|
||||
"cfg_file": '6843AOP_Tracking.cfg',
|
||||
"command_port": "/dev/ttyUSB0",
|
||||
"data_port": "/dev/ttyUSB1",
|
||||
"rviz": LaunchConfiguration('rviz'),
|
||||
}.items()
|
||||
)
|
||||
|
||||
ld = LaunchDescription()
|
||||
ld.add_action(rviz_arg)
|
||||
ld.add_action(global_param_node)
|
||||
ld.add_action(mmWaveCommSrv)
|
||||
ld.add_action(mmWaveQuickConfig)
|
||||
ld.add_action(ParameterParser)
|
||||
ld.add_action(DataHandlerClass)
|
||||
ld.add_action(Rviz2)
|
||||
ld.add_action(iwr6843_include)
|
||||
|
||||
return ld
|
||||
|
||||
@@ -1,118 +1,29 @@
|
||||
import os
|
||||
from launch import LaunchDescription, conditions
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import DeclareLaunchArgument
|
||||
from launch.actions import IncludeLaunchDescription
|
||||
from launch.substitutions import LaunchConfiguration
|
||||
from launch_ros.actions import Node
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
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'
|
||||
)
|
||||
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
|
||||
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"
|
||||
|
||||
ConfigParameters = os.path.join(
|
||||
my_package_dir,
|
||||
'config',
|
||||
'global_params.yaml',
|
||||
'launch/*.rviz'
|
||||
)
|
||||
global_param_node = Node(
|
||||
package='ti_mmwave_rospkg',
|
||||
executable='ConfigParameterServer',
|
||||
name='ConfigParameterServer',
|
||||
parameters=[ConfigParameters]
|
||||
)
|
||||
|
||||
mmWaveCommSrv = Node(
|
||||
package="ti_mmwave_rospkg",
|
||||
executable="mmWaveCommSrv",
|
||||
name="mmWaveCommSrv",
|
||||
output="screen",
|
||||
emulate_tty=True,
|
||||
parameters=[
|
||||
{"command_port": command_port},
|
||||
{"command_rate": command_rate},
|
||||
{"data_port": data_port},
|
||||
{"data_rate": data_rate},
|
||||
{"max_allowed_elevation_angle_deg": "90"},
|
||||
{"max_allowed_azimuth_angle_deg": "90"},
|
||||
{"frame_id": "/ti_mmwave_0"},
|
||||
{"mmwavecli_name": name},
|
||||
{"mmwavecli_cfg": path}
|
||||
]
|
||||
)
|
||||
|
||||
mmWaveQuickConfig = Node(
|
||||
package="ti_mmwave_rospkg",
|
||||
executable="mmWaveQuickConfig",
|
||||
name="mmWaveQuickConfig",
|
||||
output="screen",
|
||||
emulate_tty=True,
|
||||
parameters=[
|
||||
{"mmwavecli_name": name},
|
||||
{"mmwavecli_cfg": path}
|
||||
]
|
||||
)
|
||||
|
||||
ParameterParser = Node(
|
||||
package="ti_mmwave_rospkg",
|
||||
executable="ParameterParser",
|
||||
name="ParameterParser",
|
||||
output="screen",
|
||||
emulate_tty=True,
|
||||
parameters=[
|
||||
{"device_name": device},
|
||||
{"mmwavecli_name": name},
|
||||
{"mmwavecli_cfg": path}
|
||||
]
|
||||
)
|
||||
|
||||
DataHandlerClass = Node(
|
||||
package="ti_mmwave_rospkg",
|
||||
executable="DataHandlerClass",
|
||||
name="DataHandlerClass",
|
||||
output="screen",
|
||||
emulate_tty=True,
|
||||
parameters=[
|
||||
{"mmwavecli_name": name},
|
||||
{"mmwavecli_cfg": path},
|
||||
{"data_port": data_port},
|
||||
{"data_rate": data_rate}
|
||||
]
|
||||
|
||||
)
|
||||
|
||||
Rviz2 = Node(
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
arguments=['-d', os.path.join(my_package_dir, 'launch', 'rviz.rviz')],
|
||||
condition=conditions.IfCondition(rviz_enabled) # only launch RViz if the argument is true
|
||||
# include IWR6843.py
|
||||
package_dir = get_package_share_directory('ti_mmwave_rospkg')
|
||||
iwr6843_include = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(os.path.join(package_dir,'launch','IWR6843.py')),
|
||||
launch_arguments={
|
||||
"cfg_file": '6843ISK_Occupancy.cfg',
|
||||
"command_port": "/dev/ttyUSB0",
|
||||
"data_port": "/dev/ttyUSB1",
|
||||
"rviz": LaunchConfiguration('rviz'),
|
||||
}.items()
|
||||
)
|
||||
|
||||
ld = LaunchDescription()
|
||||
ld.add_action(rviz_arg)
|
||||
ld.add_action(global_param_node)
|
||||
ld.add_action(mmWaveCommSrv)
|
||||
ld.add_action(mmWaveQuickConfig)
|
||||
ld.add_action(ParameterParser)
|
||||
ld.add_action(DataHandlerClass)
|
||||
ld.add_action(Rviz2)
|
||||
ld.add_action(iwr6843_include)
|
||||
|
||||
return ld
|
||||
|
||||
@@ -1,118 +1,29 @@
|
||||
import os
|
||||
from launch import LaunchDescription, conditions
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import DeclareLaunchArgument
|
||||
from launch.actions import IncludeLaunchDescription
|
||||
from launch.substitutions import LaunchConfiguration
|
||||
from launch_ros.actions import Node
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
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'
|
||||
)
|
||||
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
|
||||
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"
|
||||
|
||||
ConfigParameters = os.path.join(
|
||||
my_package_dir,
|
||||
'config',
|
||||
'global_params.yaml',
|
||||
'launch/*.rviz'
|
||||
)
|
||||
global_param_node = Node(
|
||||
package='ti_mmwave_rospkg',
|
||||
executable='ConfigParameterServer',
|
||||
name='ConfigParameterServer',
|
||||
parameters=[ConfigParameters]
|
||||
)
|
||||
|
||||
mmWaveCommSrv = Node(
|
||||
package="ti_mmwave_rospkg",
|
||||
executable="mmWaveCommSrv",
|
||||
name="mmWaveCommSrv",
|
||||
output="screen",
|
||||
emulate_tty=True,
|
||||
parameters=[
|
||||
{"command_port": command_port},
|
||||
{"command_rate": command_rate},
|
||||
{"data_port": data_port},
|
||||
{"data_rate": data_rate},
|
||||
{"max_allowed_elevation_angle_deg": "90"},
|
||||
{"max_allowed_azimuth_angle_deg": "90"},
|
||||
{"frame_id": "/ti_mmwave_0"},
|
||||
{"mmwavecli_name": name},
|
||||
{"mmwavecli_cfg": path}
|
||||
]
|
||||
)
|
||||
|
||||
mmWaveQuickConfig = Node(
|
||||
package="ti_mmwave_rospkg",
|
||||
executable="mmWaveQuickConfig",
|
||||
name="mmWaveQuickConfig",
|
||||
output="screen",
|
||||
emulate_tty=True,
|
||||
parameters=[
|
||||
{"mmwavecli_name": name},
|
||||
{"mmwavecli_cfg": path}
|
||||
]
|
||||
)
|
||||
|
||||
ParameterParser = Node(
|
||||
package="ti_mmwave_rospkg",
|
||||
executable="ParameterParser",
|
||||
name="ParameterParser",
|
||||
output="screen",
|
||||
emulate_tty=True,
|
||||
parameters=[
|
||||
{"device_name": device},
|
||||
{"mmwavecli_name": name},
|
||||
{"mmwavecli_cfg": path}
|
||||
]
|
||||
)
|
||||
|
||||
DataHandlerClass = Node(
|
||||
package="ti_mmwave_rospkg",
|
||||
executable="DataHandlerClass",
|
||||
name="DataHandlerClass",
|
||||
output="screen",
|
||||
emulate_tty=True,
|
||||
parameters=[
|
||||
{"mmwavecli_name": name},
|
||||
{"mmwavecli_cfg": path},
|
||||
{"data_port": data_port},
|
||||
{"data_rate": data_rate}
|
||||
]
|
||||
|
||||
)
|
||||
|
||||
Rviz2 = Node(
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
arguments=['-d', os.path.join(my_package_dir, 'launch', 'rviz.rviz')],
|
||||
condition=conditions.IfCondition(rviz_enabled) # only launch RViz if the argument is true
|
||||
# include IWR6843.py
|
||||
package_dir = get_package_share_directory('ti_mmwave_rospkg')
|
||||
iwr6843_include = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(os.path.join(package_dir,'launch','IWR6843.py')),
|
||||
launch_arguments={
|
||||
"cfg_file": '6843ISK_Standard.cfg',
|
||||
"command_port": "/dev/ttyUSB0",
|
||||
"data_port": "/dev/ttyUSB1",
|
||||
"rviz": LaunchConfiguration('rviz'),
|
||||
}.items()
|
||||
)
|
||||
|
||||
ld = LaunchDescription()
|
||||
ld.add_action(rviz_arg)
|
||||
ld.add_action(global_param_node)
|
||||
ld.add_action(mmWaveCommSrv)
|
||||
ld.add_action(mmWaveQuickConfig)
|
||||
ld.add_action(ParameterParser)
|
||||
ld.add_action(DataHandlerClass)
|
||||
ld.add_action(Rviz2)
|
||||
ld.add_action(iwr6843_include)
|
||||
|
||||
return ld
|
||||
|
||||
@@ -1,118 +1,29 @@
|
||||
import os
|
||||
from launch import LaunchDescription, conditions
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import DeclareLaunchArgument
|
||||
from launch.actions import IncludeLaunchDescription
|
||||
from launch.substitutions import LaunchConfiguration
|
||||
from launch_ros.actions import Node
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
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'
|
||||
)
|
||||
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
|
||||
my_package_dir = get_package_share_directory('ti_mmwave_rospkg')
|
||||
path = os.path.join(my_package_dir,'cfg','6843ISK_Tracking.cfg')
|
||||
device = "6843"
|
||||
name = "/mmWaveCLI"
|
||||
command_port = "/dev/ttyUSB0"
|
||||
command_rate = "115200"
|
||||
data_port = "/dev/ttyUSB1"
|
||||
data_rate = "921600"
|
||||
|
||||
ConfigParameters = os.path.join(
|
||||
my_package_dir,
|
||||
'config',
|
||||
'global_params.yaml',
|
||||
'launch/*.rviz'
|
||||
)
|
||||
global_param_node = Node(
|
||||
package='ti_mmwave_rospkg',
|
||||
executable='ConfigParameterServer',
|
||||
name='ConfigParameterServer',
|
||||
parameters=[ConfigParameters]
|
||||
)
|
||||
|
||||
mmWaveCommSrv = Node(
|
||||
package="ti_mmwave_rospkg",
|
||||
executable="mmWaveCommSrv",
|
||||
name="mmWaveCommSrv",
|
||||
output="screen",
|
||||
emulate_tty=True,
|
||||
parameters=[
|
||||
{"command_port": command_port},
|
||||
{"command_rate": command_rate},
|
||||
{"data_port": data_port},
|
||||
{"data_rate": data_rate},
|
||||
{"max_allowed_elevation_angle_deg": "90"},
|
||||
{"max_allowed_azimuth_angle_deg": "90"},
|
||||
{"frame_id": "/ti_mmwave_0"},
|
||||
{"mmwavecli_name": name},
|
||||
{"mmwavecli_cfg": path}
|
||||
]
|
||||
)
|
||||
|
||||
mmWaveQuickConfig = Node(
|
||||
package="ti_mmwave_rospkg",
|
||||
executable="mmWaveQuickConfig",
|
||||
name="mmWaveQuickConfig",
|
||||
output="screen",
|
||||
emulate_tty=True,
|
||||
parameters=[
|
||||
{"mmwavecli_name": name},
|
||||
{"mmwavecli_cfg": path}
|
||||
]
|
||||
)
|
||||
|
||||
ParameterParser = Node(
|
||||
package="ti_mmwave_rospkg",
|
||||
executable="ParameterParser",
|
||||
name="ParameterParser",
|
||||
output="screen",
|
||||
emulate_tty=True,
|
||||
parameters=[
|
||||
{"device_name": device},
|
||||
{"mmwavecli_name": name},
|
||||
{"mmwavecli_cfg": path}
|
||||
]
|
||||
)
|
||||
|
||||
DataHandlerClass = Node(
|
||||
package="ti_mmwave_rospkg",
|
||||
executable="DataHandlerClass",
|
||||
name="DataHandlerClass",
|
||||
output="screen",
|
||||
emulate_tty=True,
|
||||
parameters=[
|
||||
{"mmwavecli_name": name},
|
||||
{"mmwavecli_cfg": path},
|
||||
{"data_port": data_port},
|
||||
{"data_rate": data_rate}
|
||||
]
|
||||
|
||||
)
|
||||
|
||||
Rviz2 = Node(
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
arguments=['-d', os.path.join(my_package_dir, 'launch', 'rviz.rviz')],
|
||||
condition=conditions.IfCondition(rviz_enabled) # only launch RViz if the argument is true
|
||||
# include IWR6843.py
|
||||
package_dir = get_package_share_directory('ti_mmwave_rospkg')
|
||||
iwr6843_include = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource(os.path.join(package_dir,'launch','IWR6843.py')),
|
||||
launch_arguments={
|
||||
"cfg_file": '6843ISK_Tracking.cfg',
|
||||
"command_port": "/dev/ttyUSB0",
|
||||
"data_port": "/dev/ttyUSB1",
|
||||
"rviz": LaunchConfiguration('rviz'),
|
||||
}.items()
|
||||
)
|
||||
|
||||
ld = LaunchDescription()
|
||||
ld.add_action(rviz_arg)
|
||||
ld.add_action(global_param_node)
|
||||
ld.add_action(mmWaveCommSrv)
|
||||
ld.add_action(mmWaveQuickConfig)
|
||||
ld.add_action(ParameterParser)
|
||||
ld.add_action(DataHandlerClass)
|
||||
ld.add_action(Rviz2)
|
||||
ld.add_action(iwr6843_include)
|
||||
|
||||
return ld
|
||||
|
||||
131
ros2_driver/src/ti_mmwave_rospkg/launch/IWR6843.py
Normal file
131
ros2_driver/src/ti_mmwave_rospkg/launch/IWR6843.py
Normal file
@@ -0,0 +1,131 @@
|
||||
import os
|
||||
from launch import LaunchDescription, conditions
|
||||
from launch.actions import DeclareLaunchArgument
|
||||
from launch.substitutions import LaunchConfiguration
|
||||
from launch_ros.actions import Node
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
|
||||
|
||||
def generate_launch_description():
|
||||
|
||||
# Declare the launch argument
|
||||
cfg_file_arg = DeclareLaunchArgument(
|
||||
'cfg_file',
|
||||
default_value='6843ISK_Tracking.cfg'
|
||||
)
|
||||
|
||||
command_port_arg = DeclareLaunchArgument(
|
||||
'command_port',
|
||||
default_value='/dev/ttyUSB0'
|
||||
)
|
||||
|
||||
data_port_arg = DeclareLaunchArgument(
|
||||
'data_port',
|
||||
default_value='/dev/ttyUSB1'
|
||||
)
|
||||
|
||||
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
|
||||
my_package_dir = get_package_share_directory('ti_mmwave_rospkg')
|
||||
cfg_file = LaunchConfiguration("cfg_file")
|
||||
mmwavecli_cfg_path = PathJoinSubstitution([my_package_dir, 'cfg', cfg_file])
|
||||
|
||||
device = "6843"
|
||||
name = "/mmWaveCLI"
|
||||
command_port = LaunchConfiguration("command_port")
|
||||
command_rate = "115200"
|
||||
data_port = LaunchConfiguration("data_port")
|
||||
data_rate = "921600"
|
||||
|
||||
ConfigParameters = os.path.join(
|
||||
my_package_dir,
|
||||
'config',
|
||||
'global_params.yaml',
|
||||
'launch/*.rviz'
|
||||
)
|
||||
global_param_node = Node(
|
||||
package='ti_mmwave_rospkg',
|
||||
executable='ConfigParameterServer',
|
||||
name='ConfigParameterServer',
|
||||
parameters=[ConfigParameters]
|
||||
)
|
||||
|
||||
mmWaveCommSrv = Node(
|
||||
package="ti_mmwave_rospkg",
|
||||
executable="mmWaveCommSrv",
|
||||
name="mmWaveCommSrv",
|
||||
output="screen",
|
||||
emulate_tty=True,
|
||||
parameters=[
|
||||
{"command_port": command_port},
|
||||
{"command_rate": command_rate},
|
||||
]
|
||||
)
|
||||
|
||||
mmWaveQuickConfig = Node(
|
||||
package="ti_mmwave_rospkg",
|
||||
executable="mmWaveQuickConfig",
|
||||
name="mmWaveQuickConfig",
|
||||
output="screen",
|
||||
emulate_tty=True,
|
||||
parameters=[
|
||||
{"mmwavecli_cfg": mmwavecli_cfg_path}
|
||||
]
|
||||
)
|
||||
|
||||
ParameterParser = Node(
|
||||
package="ti_mmwave_rospkg",
|
||||
executable="ParameterParser",
|
||||
name="ParameterParser",
|
||||
output="screen",
|
||||
emulate_tty=True,
|
||||
parameters=[
|
||||
{"device_name": device},
|
||||
{"mmwavecli_cfg": mmwavecli_cfg_path}
|
||||
]
|
||||
)
|
||||
|
||||
DataHandlerClass = Node(
|
||||
package="ti_mmwave_rospkg",
|
||||
executable="DataHandlerClass",
|
||||
name="DataHandlerClass",
|
||||
output="screen",
|
||||
emulate_tty=True,
|
||||
parameters=[
|
||||
{"data_port": data_port},
|
||||
{"data_rate": data_rate},
|
||||
{"max_allowed_elevation_angle_deg": 90},
|
||||
{"max_allowed_azimuth_angle_deg": 90},
|
||||
{"frame_id": "ti_mmwave_0"}
|
||||
]
|
||||
|
||||
)
|
||||
|
||||
Rviz2 = Node(
|
||||
package='rviz2',
|
||||
executable='rviz2',
|
||||
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(cfg_file_arg)
|
||||
ld.add_action(command_port_arg)
|
||||
ld.add_action(data_port_arg)
|
||||
ld.add_action(rviz_arg)
|
||||
ld.add_action(global_param_node)
|
||||
ld.add_action(mmWaveCommSrv)
|
||||
ld.add_action(mmWaveQuickConfig)
|
||||
ld.add_action(ParameterParser)
|
||||
ld.add_action(DataHandlerClass)
|
||||
ld.add_action(Rviz2)
|
||||
|
||||
return ld
|
||||
@@ -7,8 +7,9 @@ Panels:
|
||||
- /Global Options1
|
||||
- /Status1
|
||||
- /PointCloud21
|
||||
- /Axes1
|
||||
Splitter Ratio: 0.5
|
||||
Tree Height: 549
|
||||
Tree Height: 555
|
||||
- Class: rviz_common/Selection
|
||||
Name: Selection
|
||||
- Class: rviz_common/Tool Properties
|
||||
@@ -63,9 +64,9 @@ Visualization Manager:
|
||||
Enabled: true
|
||||
Invert Rainbow: false
|
||||
Max Color: 0; 255; 0
|
||||
Max Intensity: 20.0
|
||||
Max Intensity: 20
|
||||
Min Color: 255; 0; 0
|
||||
Min Intensity: 15.0
|
||||
Min Intensity: 15
|
||||
Name: PointCloud2
|
||||
Position Transformer: XYZ
|
||||
Selectable: true
|
||||
@@ -82,10 +83,17 @@ Visualization Manager:
|
||||
Use Fixed Frame: true
|
||||
Use rainbow: false
|
||||
Value: true
|
||||
- Class: rviz_default_plugins/Axes
|
||||
Enabled: true
|
||||
Length: 0.5
|
||||
Name: Axes
|
||||
Radius: 0.05000000074505806
|
||||
Reference Frame: ti_mmwave_0
|
||||
Value: true
|
||||
Enabled: true
|
||||
Global Options:
|
||||
Background Color: 48; 48; 48
|
||||
Fixed Frame: map
|
||||
Fixed Frame: ti_mmwave_0
|
||||
Frame Rate: 30
|
||||
Name: root
|
||||
Tools:
|
||||
@@ -154,7 +162,7 @@ Window Geometry:
|
||||
Height: 846
|
||||
Hide Left Dock: false
|
||||
Hide Right Dock: true
|
||||
QMainWindow State: 000000ff00000000fd000000040000000000000156000002b0fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002b0000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b0000002fb00fffffffb0000000800540069006d0065010000000000000450000000000000000000000354000002b000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||
QMainWindow State: 000000ff00000000fd000000040000000000000156000002b4fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000002b4000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d000002b0000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b00000025300fffffffb0000000800540069006d0065010000000000000450000000000000000000000354000002b400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||
Selection:
|
||||
collapsed: false
|
||||
Time:
|
||||
|
||||
@@ -58,5 +58,5 @@
|
||||
<export>
|
||||
<build_type>ament_cmake</build_type>
|
||||
</export>
|
||||
|
||||
|
||||
</package>
|
||||
@@ -8,24 +8,20 @@
|
||||
#include <pcl/io/pcd_io.h>
|
||||
#include <pcl_conversions/pcl_conversions.h>
|
||||
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
|
||||
using namespace std::chrono_literals;
|
||||
|
||||
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr DataUARTHandler_pub;
|
||||
rclcpp::Publisher<ti_mmwave_rospkg_msgs::msg::RadarScan>::SharedPtr radar_scan_pub;
|
||||
rclcpp::Publisher<ti_mmwave_rospkg_msgs::msg::RadarOccupancy>::SharedPtr radar_occupancy_pub;
|
||||
rclcpp::Publisher<ti_mmwave_rospkg_msgs::msg::RadarPointTrackID>::SharedPtr radar_trackid_pub;
|
||||
rclcpp::Publisher<ti_mmwave_rospkg_msgs::msg::RadarTrackArray>::SharedPtr radar_trackarray_pub;
|
||||
std::shared_ptr<sensor_msgs::msg::PointCloud2> pc2_msg_;
|
||||
DataUARTHandler* gDataHandlerPtr;
|
||||
rclcpp::Clock clocker;
|
||||
|
||||
DataUARTHandlerNode::DataUARTHandlerNode() : Node("DataUARTHandlerNode")
|
||||
{
|
||||
|
||||
this->declare_parameter("mmwavecli_name", rclcpp::PARAMETER_STRING);
|
||||
this->declare_parameter("mmwavecli_cfg", rclcpp::PARAMETER_STRING);
|
||||
// this->declare_parameter("mmwavecli_name", rclcpp::PARAMETER_STRING);
|
||||
// this->declare_parameter("mmwavecli_cfg", rclcpp::PARAMETER_STRING);
|
||||
this->declare_parameter("data_port", rclcpp::PARAMETER_STRING);
|
||||
this->declare_parameter("data_rate", rclcpp::PARAMETER_STRING);
|
||||
this->declare_parameter("max_allowed_elevation_angle_deg", rclcpp::PARAMETER_INTEGER);
|
||||
this->declare_parameter("max_allowed_azimuth_angle_deg", rclcpp::PARAMETER_INTEGER);
|
||||
this->declare_parameter("frame_id", rclcpp::PARAMETER_STRING);
|
||||
|
||||
}
|
||||
|
||||
@@ -66,7 +62,7 @@ POINT_CLOUD_REGISTER_POINT_STRUCT (mmWaveCloudType,
|
||||
|
||||
DataUARTHandler::DataUARTHandler(std::shared_ptr<rclcpp::Node> nh) : currentBufp(&pingPongBuffers[0]) , nextBufp(&pingPongBuffers[1])
|
||||
{
|
||||
DataUARTHandler_pub = nh->create_publisher<sensor_msgs::msg::PointCloud2>("/ti_mmwave/radar_scan_pcl", 100);
|
||||
radar_scan_pcl_pub = nh->create_publisher<sensor_msgs::msg::PointCloud2>("/ti_mmwave/radar_scan_pcl", 100);
|
||||
radar_scan_pub = nh->create_publisher<ti_mmwave_rospkg_msgs::msg::RadarScan>("/ti_mmwave/radar_scan", 100);
|
||||
radar_occupancy_pub = nh->create_publisher<ti_mmwave_rospkg_msgs::msg::RadarOccupancy>("/ti_mmwave/radar_occupancy", 100);
|
||||
radar_trackid_pub = nh->create_publisher<ti_mmwave_rospkg_msgs::msg::RadarPointTrackID>("/ti_mmwave/radar_point_track_id", 100);
|
||||
@@ -75,6 +71,8 @@ DataUARTHandler::DataUARTHandler(std::shared_ptr<rclcpp::Node> nh) : currentBufp
|
||||
maxAllowedAzimuthAngleDeg = 90; // Use max angle if none specified
|
||||
gDataHandlerPtr = this;
|
||||
stop_threads = false;
|
||||
|
||||
nodeHandle = nh;
|
||||
}
|
||||
|
||||
void DataUARTHandler::setFrameID(char const* myFrameID)
|
||||
@@ -418,7 +416,6 @@ void *DataUARTHandler::sortIncomingData(void)
|
||||
mmwData.numObjOut = mmwData.header.numDetectedObj;
|
||||
}
|
||||
|
||||
RScan->header.stamp = static_cast<long int>(clocker.now().seconds());
|
||||
RScan->header.frame_id = frameID;
|
||||
RScan->height = 1;
|
||||
RScan->width = mmwData.numObjOut;
|
||||
@@ -490,8 +487,8 @@ void *DataUARTHandler::sortIncomingData(void)
|
||||
RScan->points[i].z = temp[2]; // ROS standard coordinate system Z-axis is up which is the same as mmWave sensor Z-axis
|
||||
//RScan->points[i].intensity = temp[5];
|
||||
|
||||
radarscan.frame_id = frameID;
|
||||
radarscan.stamp = static_cast<long int>(clocker.now().seconds());
|
||||
radarscan.header.stamp = nodeHandle->now();
|
||||
radarscan.header.frame_id = frameID;
|
||||
radarscan.point_id = i;
|
||||
radarscan.x = temp[1];
|
||||
radarscan.y = -temp[0];
|
||||
@@ -526,8 +523,8 @@ void *DataUARTHandler::sortIncomingData(void)
|
||||
RScan->points[i].z = mmwData.newObjOut.z; // ROS standard coordinate system Z-axis is up which is the same as mmWave sensor Z-axis
|
||||
RScan->points[i].velocity = mmwData.newObjOut.velocity;
|
||||
|
||||
radarscan.frame_id = frameID;
|
||||
radarscan.stamp = static_cast<long int>(clocker.now().seconds());
|
||||
radarscan.header.stamp = nodeHandle->now();
|
||||
radarscan.header.frame_id = frameID;
|
||||
radarscan.point_id = i;
|
||||
radarscan.x = mmwData.newObjOut.y;
|
||||
radarscan.y = -mmwData.newObjOut.x;
|
||||
@@ -602,13 +599,14 @@ void *DataUARTHandler::sortIncomingData(void)
|
||||
|
||||
radaroccupancy.state = mmwData.occupancy.state;
|
||||
|
||||
if (radaroccupancy.state == 0){
|
||||
// RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"Area is clear!");
|
||||
}
|
||||
else{
|
||||
// RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"Area is OCCUPIED!");
|
||||
}
|
||||
// if (radaroccupancy.state == 0){
|
||||
// RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"Area is clear!");
|
||||
// }
|
||||
// else{
|
||||
// RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"Area is OCCUPIED!");
|
||||
// }
|
||||
|
||||
radaroccupancy.header.stamp = nodeHandle->now();
|
||||
radar_occupancy_pub->publish(radaroccupancy);
|
||||
|
||||
sorterState = CHECK_TLV_TYPE;
|
||||
@@ -693,8 +691,8 @@ void *DataUARTHandler::sortIncomingData(void)
|
||||
RScan->points[i].velocity = realDoppler;
|
||||
RScan->points[i].intensity = realSNR;
|
||||
|
||||
radarscan.frame_id = frameID;
|
||||
radarscan.stamp = clocker.now().seconds();
|
||||
radarscan.header.stamp = nodeHandle->now();
|
||||
radarscan.header.frame_id = frameID;
|
||||
|
||||
radarscan.point_id = i;
|
||||
radarscan.x = realRange * cos(realAzimuth) * cos(realElevation);
|
||||
@@ -729,8 +727,7 @@ void *DataUARTHandler::sortIncomingData(void)
|
||||
i = 0;
|
||||
offset = 0;
|
||||
mmwData.numObjOut = mmwData.header.numDetectedObj;
|
||||
radartrackarray.frame_id = frameID;
|
||||
radartrackarray.stamp = clocker.now().seconds();
|
||||
|
||||
radartrackarray.num_tracks = (int) tlvLen / 112;
|
||||
|
||||
//RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"Number of Tracks is: %d",(tlvLen / 112));
|
||||
@@ -788,8 +785,8 @@ void *DataUARTHandler::sortIncomingData(void)
|
||||
memcpy( &mmwData.newListOut.confidenceLevel, ¤tBufp->at(currentDatap), sizeof(mmwData.newListOut.confidenceLevel));
|
||||
currentDatap += ( sizeof(mmwData.newListOut.confidenceLevel) );
|
||||
|
||||
radartrackcontents.frame_id = frameID;
|
||||
radartrackcontents.stamp = clocker.now().seconds();
|
||||
radartrackcontents.header.stamp = nodeHandle->now();
|
||||
radartrackcontents.header.frame_id = frameID;
|
||||
radartrackcontents.tid = mmwData.newListOut.tid;
|
||||
radartrackcontents.posx = mmwData.newListOut.posY; // ROS standard coordinate system X-axis is forward which is the mmWave sensor Y-axis
|
||||
radartrackcontents.posy = -mmwData.newListOut.posX; // ROS standard coordinate system Y-axis is left which is the mmWave sensor -(X-axis)
|
||||
@@ -802,8 +799,10 @@ void *DataUARTHandler::sortIncomingData(void)
|
||||
radartrackcontents.accz = mmwData.newListOut.accZ;
|
||||
radartrackarray.track.push_back(radartrackcontents);
|
||||
i++;
|
||||
|
||||
}
|
||||
|
||||
radartrackarray.header.stamp = nodeHandle->now();
|
||||
radartrackarray.header.frame_id = frameID;
|
||||
radar_trackarray_pub->publish(radartrackarray);
|
||||
radartrackarray.track.clear();
|
||||
sorterState = CHECK_TLV_TYPE;
|
||||
@@ -881,8 +880,9 @@ void *DataUARTHandler::sortIncomingData(void)
|
||||
RScan->points[i].z = realZ;
|
||||
RScan->points[i].velocity = realDoppler;
|
||||
RScan->points[i].intensity = realSNR;
|
||||
radarscan.frame_id = frameID;
|
||||
radarscan.stamp = clocker.now().seconds();
|
||||
|
||||
radarscan.header.stamp = nodeHandle->now();
|
||||
radarscan.header.frame_id = frameID;
|
||||
radarscan.point_id = i;
|
||||
radarscan.x = realY;
|
||||
radarscan.y = -(realX);
|
||||
@@ -932,12 +932,12 @@ void *DataUARTHandler::sortIncomingData(void)
|
||||
|
||||
// throw away first track in order to allign with PointCloud
|
||||
// if (frameID == 0){
|
||||
radartrackid.frame_id = frameID;
|
||||
radartrackid.header.frame_id = frameID;
|
||||
// }
|
||||
// else{
|
||||
// radartrackid.header.frame_id = frameID - 1;
|
||||
// }
|
||||
radartrackid.stamp = clocker.now().seconds();
|
||||
radartrackid.header.stamp = nodeHandle->now();
|
||||
radartrackid.tid = mmwData.newIndexOut.targetID;
|
||||
|
||||
radar_trackid_pub->publish(radartrackid);
|
||||
@@ -1040,8 +1040,9 @@ void *DataUARTHandler::sortIncomingData(void)
|
||||
}
|
||||
pc2_msg_ = std::make_shared<sensor_msgs::msg::PointCloud2>();
|
||||
pcl::toROSMsg(*RScan, *pc2_msg_);
|
||||
pc2_msg_->header.frame_id = "map";
|
||||
DataUARTHandler_pub->publish(*pc2_msg_);
|
||||
pc2_msg_->header.stamp = nodeHandle->now();
|
||||
pc2_msg_->header.frame_id = frameID;
|
||||
radar_scan_pcl_pub->publish(*pc2_msg_);
|
||||
sorterState = SWAP_BUFFERS;
|
||||
}
|
||||
else // More TLV sections to parse
|
||||
@@ -1257,17 +1258,22 @@ void DataUARTHandler::stop()
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
rclcpp::init(argc, argv);
|
||||
|
||||
auto node = std::make_shared<DataUARTHandlerNode>();
|
||||
std::string mySerialPort = node->get_parameter("data_port").as_string();
|
||||
std::string myBaudRate = node->get_parameter("data_rate").as_string();
|
||||
std::string myFrameID = "/ti_mmwave_0";
|
||||
std::string myFrameID = node->get_parameter("frame_id").as_string();
|
||||
int maxAllowedElevationAngleDeg = node->get_parameter("max_allowed_elevation_angle_deg").as_int();
|
||||
int maxAllowedAzimuthAngleDeg = node->get_parameter("max_allowed_azimuth_angle_deg").as_int();
|
||||
|
||||
DataUARTHandler d(node);
|
||||
d.setFrameID(myFrameID.c_str());
|
||||
d.setUARTPort(mySerialPort.c_str());
|
||||
d.setBaudRate(std::stoi(myBaudRate));
|
||||
d.setMaxAllowedElevationAngleDeg(90);
|
||||
d.setMaxAllowedAzimuthAngleDeg(90);
|
||||
d.setMaxAllowedElevationAngleDeg(maxAllowedElevationAngleDeg);
|
||||
d.setMaxAllowedAzimuthAngleDeg(maxAllowedAzimuthAngleDeg);
|
||||
d.start();
|
||||
|
||||
rclcpp::spin(node);
|
||||
rclcpp::shutdown();
|
||||
}
|
||||
@@ -15,17 +15,17 @@
|
||||
|
||||
std::shared_ptr<rclcpp::Node> nodeptr3 = nullptr;
|
||||
|
||||
class ParameterParser : public rclcpp::Node
|
||||
{
|
||||
class ParameterParser : public rclcpp::Node
|
||||
{
|
||||
public:
|
||||
ParameterParser() : Node("ParameterParser")
|
||||
{
|
||||
this->declare_parameter("device_name", rclcpp::PARAMETER_STRING);
|
||||
this->declare_parameter("device_name", rclcpp::PARAMETER_STRING);
|
||||
this->declare_parameter("mmwavecli_name", rclcpp::PARAMETER_STRING);
|
||||
this->declare_parameter("mmwavecli_cfg", rclcpp::PARAMETER_STRING);
|
||||
parameters_client_test = std::make_shared<rclcpp::AsyncParametersClient>(this, "/ConfigParameterServer");
|
||||
parameters_client_test->wait_for_service();
|
||||
auto parameters_future = parameters_client_test->get_parameters({
|
||||
auto parameters_future = parameters_client_test->get_parameters({
|
||||
"/ti_mmwave/startFreq",
|
||||
"/ti_mmwave/idleTime",
|
||||
"/ti_mmwave/adcStartTime",
|
||||
@@ -44,7 +44,7 @@ public:
|
||||
"/ti_mmwave/zoneMinY",
|
||||
"/ti_mmwave/zoneMaxY",
|
||||
"/ti_mmwave/zoneMinZ",
|
||||
"/ti_mmwave/zoneMaxZ"
|
||||
"/ti_mmwave/zoneMaxZ"
|
||||
},
|
||||
std::bind(&ParameterParser::callbackGlobalParam, this, std::placeholders::_1));
|
||||
}
|
||||
@@ -89,19 +89,19 @@ int main(int argc, char **argv) {
|
||||
std::ifstream myCfgParam;
|
||||
std::string str_param;
|
||||
std::string deviceName = nodeptr3->get_parameter("device_name").as_string();
|
||||
std::string mmWaveCLIname = nodeptr3->get_parameter("mmwavecli_name").as_string();
|
||||
// std::string mmWaveCLIname = nodeptr3->get_parameter("mmwavecli_name").as_string();
|
||||
std::string mmWaveCLIcfg = nodeptr3->get_parameter("mmwavecli_cfg").as_string();
|
||||
auto parameters_client = std::make_shared<rclcpp::AsyncParametersClient>(nodeptr3, "/ConfigParameterServer");
|
||||
myCfgParam.open(mmWaveCLIcfg);
|
||||
|
||||
if (deviceName.compare("6432") != 0)
|
||||
{
|
||||
if (myCfgParam.is_open())
|
||||
if (myCfgParam.is_open())
|
||||
{
|
||||
while( std::getline(myCfgParam, str_param))
|
||||
while( std::getline(myCfgParam, str_param))
|
||||
{
|
||||
str_param.erase(std::remove(str_param.begin(), str_param.end(), '\r'), str_param.end());
|
||||
if (!(std::regex_match(str_param, std::regex("^\\s*%.*")) || std::regex_match(str_param, std::regex("^\\s*"))))
|
||||
if (!(std::regex_match(str_param, std::regex("^\\s*%.*")) || std::regex_match(str_param, std::regex("^\\s*"))))
|
||||
{
|
||||
//RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"myParams equals %s\n", str_param.c_str() );
|
||||
std::istringstream ss(str_param);
|
||||
@@ -111,7 +111,7 @@ int main(int argc, char **argv) {
|
||||
v.push_back(token);
|
||||
}
|
||||
|
||||
if (!v[0].compare("profileCfg"))
|
||||
if (!v[0].compare("profileCfg"))
|
||||
{
|
||||
//RCLCPP_INFO(this->get_logger(), "ProfileCfg");
|
||||
parameters_client->set_parameters(
|
||||
@@ -132,8 +132,8 @@ int main(int argc, char **argv) {
|
||||
freqSlopeConst = std::stof(v[8]);
|
||||
numAdcSamples = std::stof(v[10]);
|
||||
digOutSampleRate = std::stof(v[11]);
|
||||
}
|
||||
else if (!v[0].compare("frameCfg"))
|
||||
}
|
||||
else if (!v[0].compare("frameCfg"))
|
||||
{
|
||||
parameters_client->set_parameters(
|
||||
{
|
||||
@@ -149,8 +149,8 @@ int main(int argc, char **argv) {
|
||||
numLoops = std::stoi(v[3]);
|
||||
numFrames = std::stoi(v[4]);
|
||||
framePeriodicity = std::stof(v[5]);
|
||||
}
|
||||
else if (!v[0].compare("zoneDef"))
|
||||
}
|
||||
else if (!v[0].compare("zoneDef"))
|
||||
{
|
||||
parameters_client->set_parameters(
|
||||
{
|
||||
@@ -169,7 +169,7 @@ int main(int argc, char **argv) {
|
||||
zoneMinZ = std::stoi(v[6]);
|
||||
zoneMaxZ = std::stoi(v[7]);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -182,7 +182,7 @@ int main(int argc, char **argv) {
|
||||
float adc_duration = nr / fs;
|
||||
float BW = adc_duration * kf;
|
||||
float PRI = (idleTime + rampEndTime) * 1e-6;
|
||||
float fc = startFreq * 1e9 + kf * (adcStartTime * 1e-6 + adc_duration / 2);
|
||||
float fc = startFreq * 1e9 + kf * (adcStartTime * 1e-6 + adc_duration / 2);
|
||||
float vrange = c0 / (2 * BW);
|
||||
float max_range = nr * vrange;
|
||||
float max_vel = c0 / (2 * fc * PRI) / ntx;
|
||||
|
||||
@@ -1 +0,0 @@
|
||||
colcon
|
||||
@@ -1 +0,0 @@
|
||||
isolated
|
||||
@@ -1,404 +0,0 @@
|
||||
# Copyright 2016-2019 Dirk Thomas
|
||||
# Licensed under the Apache License, Version 2.0
|
||||
|
||||
import argparse
|
||||
from collections import OrderedDict
|
||||
import os
|
||||
from pathlib import Path
|
||||
import sys
|
||||
|
||||
|
||||
FORMAT_STR_COMMENT_LINE = '# {comment}'
|
||||
FORMAT_STR_SET_ENV_VAR = 'Set-Item -Path "Env:{name}" -Value "{value}"'
|
||||
FORMAT_STR_USE_ENV_VAR = '$env:{name}'
|
||||
FORMAT_STR_INVOKE_SCRIPT = '_colcon_prefix_powershell_source_script "{script_path}"'
|
||||
FORMAT_STR_REMOVE_LEADING_SEPARATOR = ''
|
||||
FORMAT_STR_REMOVE_TRAILING_SEPARATOR = ''
|
||||
|
||||
DSV_TYPE_APPEND_NON_DUPLICATE = 'append-non-duplicate'
|
||||
DSV_TYPE_PREPEND_NON_DUPLICATE = 'prepend-non-duplicate'
|
||||
DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS = 'prepend-non-duplicate-if-exists'
|
||||
DSV_TYPE_SET = 'set'
|
||||
DSV_TYPE_SET_IF_UNSET = 'set-if-unset'
|
||||
DSV_TYPE_SOURCE = 'source'
|
||||
|
||||
|
||||
def main(argv=sys.argv[1:]): # noqa: D103
|
||||
parser = argparse.ArgumentParser(
|
||||
description='Output shell commands for the packages in topological '
|
||||
'order')
|
||||
parser.add_argument(
|
||||
'primary_extension',
|
||||
help='The file extension of the primary shell')
|
||||
parser.add_argument(
|
||||
'additional_extension', nargs='?',
|
||||
help='The additional file extension to be considered')
|
||||
parser.add_argument(
|
||||
'--merged-install', action='store_true',
|
||||
help='All install prefixes are merged into a single location')
|
||||
args = parser.parse_args(argv)
|
||||
|
||||
packages = get_packages(Path(__file__).parent, args.merged_install)
|
||||
|
||||
ordered_packages = order_packages(packages)
|
||||
for pkg_name in ordered_packages:
|
||||
if _include_comments():
|
||||
print(
|
||||
FORMAT_STR_COMMENT_LINE.format_map(
|
||||
{'comment': 'Package: ' + pkg_name}))
|
||||
prefix = os.path.abspath(os.path.dirname(__file__))
|
||||
if not args.merged_install:
|
||||
prefix = os.path.join(prefix, pkg_name)
|
||||
for line in get_commands(
|
||||
pkg_name, prefix, args.primary_extension,
|
||||
args.additional_extension
|
||||
):
|
||||
print(line)
|
||||
|
||||
for line in _remove_ending_separators():
|
||||
print(line)
|
||||
|
||||
|
||||
def get_packages(prefix_path, merged_install):
|
||||
"""
|
||||
Find packages based on colcon-specific files created during installation.
|
||||
|
||||
:param Path prefix_path: The install prefix path of all packages
|
||||
:param bool merged_install: The flag if the packages are all installed
|
||||
directly in the prefix or if each package is installed in a subdirectory
|
||||
named after the package
|
||||
:returns: A mapping from the package name to the set of runtime
|
||||
dependencies
|
||||
:rtype: dict
|
||||
"""
|
||||
packages = {}
|
||||
# since importing colcon_core isn't feasible here the following constant
|
||||
# must match colcon_core.location.get_relative_package_index_path()
|
||||
subdirectory = 'share/colcon-core/packages'
|
||||
if merged_install:
|
||||
# return if workspace is empty
|
||||
if not (prefix_path / subdirectory).is_dir():
|
||||
return packages
|
||||
# find all files in the subdirectory
|
||||
for p in (prefix_path / subdirectory).iterdir():
|
||||
if not p.is_file():
|
||||
continue
|
||||
if p.name.startswith('.'):
|
||||
continue
|
||||
add_package_runtime_dependencies(p, packages)
|
||||
else:
|
||||
# for each subdirectory look for the package specific file
|
||||
for p in prefix_path.iterdir():
|
||||
if not p.is_dir():
|
||||
continue
|
||||
if p.name.startswith('.'):
|
||||
continue
|
||||
p = p / subdirectory / p.name
|
||||
if p.is_file():
|
||||
add_package_runtime_dependencies(p, packages)
|
||||
|
||||
# remove unknown dependencies
|
||||
pkg_names = set(packages.keys())
|
||||
for k in packages.keys():
|
||||
packages[k] = {d for d in packages[k] if d in pkg_names}
|
||||
|
||||
return packages
|
||||
|
||||
|
||||
def add_package_runtime_dependencies(path, packages):
|
||||
"""
|
||||
Check the path and if it exists extract the packages runtime dependencies.
|
||||
|
||||
:param Path path: The resource file containing the runtime dependencies
|
||||
:param dict packages: A mapping from package names to the sets of runtime
|
||||
dependencies to add to
|
||||
"""
|
||||
content = path.read_text()
|
||||
dependencies = set(content.split(os.pathsep) if content else [])
|
||||
packages[path.name] = dependencies
|
||||
|
||||
|
||||
def order_packages(packages):
|
||||
"""
|
||||
Order packages topologically.
|
||||
|
||||
:param dict packages: A mapping from package name to the set of runtime
|
||||
dependencies
|
||||
:returns: The package names
|
||||
:rtype: list
|
||||
"""
|
||||
# select packages with no dependencies in alphabetical order
|
||||
to_be_ordered = list(packages.keys())
|
||||
ordered = []
|
||||
while to_be_ordered:
|
||||
pkg_names_without_deps = [
|
||||
name for name in to_be_ordered if not packages[name]]
|
||||
if not pkg_names_without_deps:
|
||||
reduce_cycle_set(packages)
|
||||
raise RuntimeError(
|
||||
'Circular dependency between: ' + ', '.join(sorted(packages)))
|
||||
pkg_names_without_deps.sort()
|
||||
pkg_name = pkg_names_without_deps[0]
|
||||
to_be_ordered.remove(pkg_name)
|
||||
ordered.append(pkg_name)
|
||||
# remove item from dependency lists
|
||||
for k in list(packages.keys()):
|
||||
if pkg_name in packages[k]:
|
||||
packages[k].remove(pkg_name)
|
||||
return ordered
|
||||
|
||||
|
||||
def reduce_cycle_set(packages):
|
||||
"""
|
||||
Reduce the set of packages to the ones part of the circular dependency.
|
||||
|
||||
:param dict packages: A mapping from package name to the set of runtime
|
||||
dependencies which is modified in place
|
||||
"""
|
||||
last_depended = None
|
||||
while len(packages) > 0:
|
||||
# get all remaining dependencies
|
||||
depended = set()
|
||||
for pkg_name, dependencies in packages.items():
|
||||
depended = depended.union(dependencies)
|
||||
# remove all packages which are not dependent on
|
||||
for name in list(packages.keys()):
|
||||
if name not in depended:
|
||||
del packages[name]
|
||||
if last_depended:
|
||||
# if remaining packages haven't changed return them
|
||||
if last_depended == depended:
|
||||
return packages.keys()
|
||||
# otherwise reduce again
|
||||
last_depended = depended
|
||||
|
||||
|
||||
def _include_comments():
|
||||
# skipping comment lines when COLCON_TRACE is not set speeds up the
|
||||
# processing especially on Windows
|
||||
return bool(os.environ.get('COLCON_TRACE'))
|
||||
|
||||
|
||||
def get_commands(pkg_name, prefix, primary_extension, additional_extension):
|
||||
commands = []
|
||||
package_dsv_path = os.path.join(prefix, 'share', pkg_name, 'package.dsv')
|
||||
if os.path.exists(package_dsv_path):
|
||||
commands += process_dsv_file(
|
||||
package_dsv_path, prefix, primary_extension, additional_extension)
|
||||
return commands
|
||||
|
||||
|
||||
def process_dsv_file(
|
||||
dsv_path, prefix, primary_extension=None, additional_extension=None
|
||||
):
|
||||
commands = []
|
||||
if _include_comments():
|
||||
commands.append(FORMAT_STR_COMMENT_LINE.format_map({'comment': dsv_path}))
|
||||
with open(dsv_path, 'r') as h:
|
||||
content = h.read()
|
||||
lines = content.splitlines()
|
||||
|
||||
basenames = OrderedDict()
|
||||
for i, line in enumerate(lines):
|
||||
# skip over empty or whitespace-only lines
|
||||
if not line.strip():
|
||||
continue
|
||||
try:
|
||||
type_, remainder = line.split(';', 1)
|
||||
except ValueError:
|
||||
raise RuntimeError(
|
||||
"Line %d in '%s' doesn't contain a semicolon separating the "
|
||||
'type from the arguments' % (i + 1, dsv_path))
|
||||
if type_ != DSV_TYPE_SOURCE:
|
||||
# handle non-source lines
|
||||
try:
|
||||
commands += handle_dsv_types_except_source(
|
||||
type_, remainder, prefix)
|
||||
except RuntimeError as e:
|
||||
raise RuntimeError(
|
||||
"Line %d in '%s' %s" % (i + 1, dsv_path, e)) from e
|
||||
else:
|
||||
# group remaining source lines by basename
|
||||
path_without_ext, ext = os.path.splitext(remainder)
|
||||
if path_without_ext not in basenames:
|
||||
basenames[path_without_ext] = set()
|
||||
assert ext.startswith('.')
|
||||
ext = ext[1:]
|
||||
if ext in (primary_extension, additional_extension):
|
||||
basenames[path_without_ext].add(ext)
|
||||
|
||||
# add the dsv extension to each basename if the file exists
|
||||
for basename, extensions in basenames.items():
|
||||
if not os.path.isabs(basename):
|
||||
basename = os.path.join(prefix, basename)
|
||||
if os.path.exists(basename + '.dsv'):
|
||||
extensions.add('dsv')
|
||||
|
||||
for basename, extensions in basenames.items():
|
||||
if not os.path.isabs(basename):
|
||||
basename = os.path.join(prefix, basename)
|
||||
if 'dsv' in extensions:
|
||||
# process dsv files recursively
|
||||
commands += process_dsv_file(
|
||||
basename + '.dsv', prefix, primary_extension=primary_extension,
|
||||
additional_extension=additional_extension)
|
||||
elif primary_extension in extensions and len(extensions) == 1:
|
||||
# source primary-only files
|
||||
commands += [
|
||||
FORMAT_STR_INVOKE_SCRIPT.format_map({
|
||||
'prefix': prefix,
|
||||
'script_path': basename + '.' + primary_extension})]
|
||||
elif additional_extension in extensions:
|
||||
# source non-primary files
|
||||
commands += [
|
||||
FORMAT_STR_INVOKE_SCRIPT.format_map({
|
||||
'prefix': prefix,
|
||||
'script_path': basename + '.' + additional_extension})]
|
||||
|
||||
return commands
|
||||
|
||||
|
||||
def handle_dsv_types_except_source(type_, remainder, prefix):
|
||||
commands = []
|
||||
if type_ in (DSV_TYPE_SET, DSV_TYPE_SET_IF_UNSET):
|
||||
try:
|
||||
env_name, value = remainder.split(';', 1)
|
||||
except ValueError:
|
||||
raise RuntimeError(
|
||||
"doesn't contain a semicolon separating the environment name "
|
||||
'from the value')
|
||||
try_prefixed_value = os.path.join(prefix, value) if value else prefix
|
||||
if os.path.exists(try_prefixed_value):
|
||||
value = try_prefixed_value
|
||||
if type_ == DSV_TYPE_SET:
|
||||
commands += _set(env_name, value)
|
||||
elif type_ == DSV_TYPE_SET_IF_UNSET:
|
||||
commands += _set_if_unset(env_name, value)
|
||||
else:
|
||||
assert False
|
||||
elif type_ in (
|
||||
DSV_TYPE_APPEND_NON_DUPLICATE,
|
||||
DSV_TYPE_PREPEND_NON_DUPLICATE,
|
||||
DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS
|
||||
):
|
||||
try:
|
||||
env_name_and_values = remainder.split(';')
|
||||
except ValueError:
|
||||
raise RuntimeError(
|
||||
"doesn't contain a semicolon separating the environment name "
|
||||
'from the values')
|
||||
env_name = env_name_and_values[0]
|
||||
values = env_name_and_values[1:]
|
||||
for value in values:
|
||||
if not value:
|
||||
value = prefix
|
||||
elif not os.path.isabs(value):
|
||||
value = os.path.join(prefix, value)
|
||||
if (
|
||||
type_ == DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS and
|
||||
not os.path.exists(value)
|
||||
):
|
||||
comment = f'skip extending {env_name} with not existing ' \
|
||||
f'path: {value}'
|
||||
if _include_comments():
|
||||
commands.append(
|
||||
FORMAT_STR_COMMENT_LINE.format_map({'comment': comment}))
|
||||
elif type_ == DSV_TYPE_APPEND_NON_DUPLICATE:
|
||||
commands += _append_unique_value(env_name, value)
|
||||
else:
|
||||
commands += _prepend_unique_value(env_name, value)
|
||||
else:
|
||||
raise RuntimeError(
|
||||
'contains an unknown environment hook type: ' + type_)
|
||||
return commands
|
||||
|
||||
|
||||
env_state = {}
|
||||
|
||||
|
||||
def _append_unique_value(name, value):
|
||||
global env_state
|
||||
if name not in env_state:
|
||||
if os.environ.get(name):
|
||||
env_state[name] = set(os.environ[name].split(os.pathsep))
|
||||
else:
|
||||
env_state[name] = set()
|
||||
# append even if the variable has not been set yet, in case a shell script sets the
|
||||
# same variable without the knowledge of this Python script.
|
||||
# later _remove_ending_separators() will cleanup any unintentional leading separator
|
||||
extend = FORMAT_STR_USE_ENV_VAR.format_map({'name': name}) + os.pathsep
|
||||
line = FORMAT_STR_SET_ENV_VAR.format_map(
|
||||
{'name': name, 'value': extend + value})
|
||||
if value not in env_state[name]:
|
||||
env_state[name].add(value)
|
||||
else:
|
||||
if not _include_comments():
|
||||
return []
|
||||
line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line})
|
||||
return [line]
|
||||
|
||||
|
||||
def _prepend_unique_value(name, value):
|
||||
global env_state
|
||||
if name not in env_state:
|
||||
if os.environ.get(name):
|
||||
env_state[name] = set(os.environ[name].split(os.pathsep))
|
||||
else:
|
||||
env_state[name] = set()
|
||||
# prepend even if the variable has not been set yet, in case a shell script sets the
|
||||
# same variable without the knowledge of this Python script.
|
||||
# later _remove_ending_separators() will cleanup any unintentional trailing separator
|
||||
extend = os.pathsep + FORMAT_STR_USE_ENV_VAR.format_map({'name': name})
|
||||
line = FORMAT_STR_SET_ENV_VAR.format_map(
|
||||
{'name': name, 'value': value + extend})
|
||||
if value not in env_state[name]:
|
||||
env_state[name].add(value)
|
||||
else:
|
||||
if not _include_comments():
|
||||
return []
|
||||
line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line})
|
||||
return [line]
|
||||
|
||||
|
||||
# generate commands for removing prepended underscores
|
||||
def _remove_ending_separators():
|
||||
# do nothing if the shell extension does not implement the logic
|
||||
if FORMAT_STR_REMOVE_TRAILING_SEPARATOR is None:
|
||||
return []
|
||||
|
||||
global env_state
|
||||
commands = []
|
||||
for name in env_state:
|
||||
# skip variables that already had values before this script started prepending
|
||||
if name in os.environ:
|
||||
continue
|
||||
commands += [
|
||||
FORMAT_STR_REMOVE_LEADING_SEPARATOR.format_map({'name': name}),
|
||||
FORMAT_STR_REMOVE_TRAILING_SEPARATOR.format_map({'name': name})]
|
||||
return commands
|
||||
|
||||
|
||||
def _set(name, value):
|
||||
global env_state
|
||||
env_state[name] = value
|
||||
line = FORMAT_STR_SET_ENV_VAR.format_map(
|
||||
{'name': name, 'value': value})
|
||||
return [line]
|
||||
|
||||
|
||||
def _set_if_unset(name, value):
|
||||
global env_state
|
||||
line = FORMAT_STR_SET_ENV_VAR.format_map(
|
||||
{'name': name, 'value': value})
|
||||
if env_state.get(name, os.environ.get(name)):
|
||||
line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line})
|
||||
return [line]
|
||||
|
||||
|
||||
if __name__ == '__main__': # pragma: no cover
|
||||
try:
|
||||
rc = main()
|
||||
except RuntimeError as e:
|
||||
print(str(e), file=sys.stderr)
|
||||
rc = 1
|
||||
sys.exit(rc)
|
||||
@@ -1,404 +0,0 @@
|
||||
# Copyright 2016-2019 Dirk Thomas
|
||||
# Licensed under the Apache License, Version 2.0
|
||||
|
||||
import argparse
|
||||
from collections import OrderedDict
|
||||
import os
|
||||
from pathlib import Path
|
||||
import sys
|
||||
|
||||
|
||||
FORMAT_STR_COMMENT_LINE = '# {comment}'
|
||||
FORMAT_STR_SET_ENV_VAR = 'export {name}="{value}"'
|
||||
FORMAT_STR_USE_ENV_VAR = '${name}'
|
||||
FORMAT_STR_INVOKE_SCRIPT = 'COLCON_CURRENT_PREFIX="{prefix}" _colcon_prefix_sh_source_script "{script_path}"'
|
||||
FORMAT_STR_REMOVE_LEADING_SEPARATOR = 'if [ "$(echo -n ${name} | head -c 1)" = ":" ]; then export {name}=${{{name}#?}} ; fi'
|
||||
FORMAT_STR_REMOVE_TRAILING_SEPARATOR = 'if [ "$(echo -n ${name} | tail -c 1)" = ":" ]; then export {name}=${{{name}%?}} ; fi'
|
||||
|
||||
DSV_TYPE_APPEND_NON_DUPLICATE = 'append-non-duplicate'
|
||||
DSV_TYPE_PREPEND_NON_DUPLICATE = 'prepend-non-duplicate'
|
||||
DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS = 'prepend-non-duplicate-if-exists'
|
||||
DSV_TYPE_SET = 'set'
|
||||
DSV_TYPE_SET_IF_UNSET = 'set-if-unset'
|
||||
DSV_TYPE_SOURCE = 'source'
|
||||
|
||||
|
||||
def main(argv=sys.argv[1:]): # noqa: D103
|
||||
parser = argparse.ArgumentParser(
|
||||
description='Output shell commands for the packages in topological '
|
||||
'order')
|
||||
parser.add_argument(
|
||||
'primary_extension',
|
||||
help='The file extension of the primary shell')
|
||||
parser.add_argument(
|
||||
'additional_extension', nargs='?',
|
||||
help='The additional file extension to be considered')
|
||||
parser.add_argument(
|
||||
'--merged-install', action='store_true',
|
||||
help='All install prefixes are merged into a single location')
|
||||
args = parser.parse_args(argv)
|
||||
|
||||
packages = get_packages(Path(__file__).parent, args.merged_install)
|
||||
|
||||
ordered_packages = order_packages(packages)
|
||||
for pkg_name in ordered_packages:
|
||||
if _include_comments():
|
||||
print(
|
||||
FORMAT_STR_COMMENT_LINE.format_map(
|
||||
{'comment': 'Package: ' + pkg_name}))
|
||||
prefix = os.path.abspath(os.path.dirname(__file__))
|
||||
if not args.merged_install:
|
||||
prefix = os.path.join(prefix, pkg_name)
|
||||
for line in get_commands(
|
||||
pkg_name, prefix, args.primary_extension,
|
||||
args.additional_extension
|
||||
):
|
||||
print(line)
|
||||
|
||||
for line in _remove_ending_separators():
|
||||
print(line)
|
||||
|
||||
|
||||
def get_packages(prefix_path, merged_install):
|
||||
"""
|
||||
Find packages based on colcon-specific files created during installation.
|
||||
|
||||
:param Path prefix_path: The install prefix path of all packages
|
||||
:param bool merged_install: The flag if the packages are all installed
|
||||
directly in the prefix or if each package is installed in a subdirectory
|
||||
named after the package
|
||||
:returns: A mapping from the package name to the set of runtime
|
||||
dependencies
|
||||
:rtype: dict
|
||||
"""
|
||||
packages = {}
|
||||
# since importing colcon_core isn't feasible here the following constant
|
||||
# must match colcon_core.location.get_relative_package_index_path()
|
||||
subdirectory = 'share/colcon-core/packages'
|
||||
if merged_install:
|
||||
# return if workspace is empty
|
||||
if not (prefix_path / subdirectory).is_dir():
|
||||
return packages
|
||||
# find all files in the subdirectory
|
||||
for p in (prefix_path / subdirectory).iterdir():
|
||||
if not p.is_file():
|
||||
continue
|
||||
if p.name.startswith('.'):
|
||||
continue
|
||||
add_package_runtime_dependencies(p, packages)
|
||||
else:
|
||||
# for each subdirectory look for the package specific file
|
||||
for p in prefix_path.iterdir():
|
||||
if not p.is_dir():
|
||||
continue
|
||||
if p.name.startswith('.'):
|
||||
continue
|
||||
p = p / subdirectory / p.name
|
||||
if p.is_file():
|
||||
add_package_runtime_dependencies(p, packages)
|
||||
|
||||
# remove unknown dependencies
|
||||
pkg_names = set(packages.keys())
|
||||
for k in packages.keys():
|
||||
packages[k] = {d for d in packages[k] if d in pkg_names}
|
||||
|
||||
return packages
|
||||
|
||||
|
||||
def add_package_runtime_dependencies(path, packages):
|
||||
"""
|
||||
Check the path and if it exists extract the packages runtime dependencies.
|
||||
|
||||
:param Path path: The resource file containing the runtime dependencies
|
||||
:param dict packages: A mapping from package names to the sets of runtime
|
||||
dependencies to add to
|
||||
"""
|
||||
content = path.read_text()
|
||||
dependencies = set(content.split(os.pathsep) if content else [])
|
||||
packages[path.name] = dependencies
|
||||
|
||||
|
||||
def order_packages(packages):
|
||||
"""
|
||||
Order packages topologically.
|
||||
|
||||
:param dict packages: A mapping from package name to the set of runtime
|
||||
dependencies
|
||||
:returns: The package names
|
||||
:rtype: list
|
||||
"""
|
||||
# select packages with no dependencies in alphabetical order
|
||||
to_be_ordered = list(packages.keys())
|
||||
ordered = []
|
||||
while to_be_ordered:
|
||||
pkg_names_without_deps = [
|
||||
name for name in to_be_ordered if not packages[name]]
|
||||
if not pkg_names_without_deps:
|
||||
reduce_cycle_set(packages)
|
||||
raise RuntimeError(
|
||||
'Circular dependency between: ' + ', '.join(sorted(packages)))
|
||||
pkg_names_without_deps.sort()
|
||||
pkg_name = pkg_names_without_deps[0]
|
||||
to_be_ordered.remove(pkg_name)
|
||||
ordered.append(pkg_name)
|
||||
# remove item from dependency lists
|
||||
for k in list(packages.keys()):
|
||||
if pkg_name in packages[k]:
|
||||
packages[k].remove(pkg_name)
|
||||
return ordered
|
||||
|
||||
|
||||
def reduce_cycle_set(packages):
|
||||
"""
|
||||
Reduce the set of packages to the ones part of the circular dependency.
|
||||
|
||||
:param dict packages: A mapping from package name to the set of runtime
|
||||
dependencies which is modified in place
|
||||
"""
|
||||
last_depended = None
|
||||
while len(packages) > 0:
|
||||
# get all remaining dependencies
|
||||
depended = set()
|
||||
for pkg_name, dependencies in packages.items():
|
||||
depended = depended.union(dependencies)
|
||||
# remove all packages which are not dependent on
|
||||
for name in list(packages.keys()):
|
||||
if name not in depended:
|
||||
del packages[name]
|
||||
if last_depended:
|
||||
# if remaining packages haven't changed return them
|
||||
if last_depended == depended:
|
||||
return packages.keys()
|
||||
# otherwise reduce again
|
||||
last_depended = depended
|
||||
|
||||
|
||||
def _include_comments():
|
||||
# skipping comment lines when COLCON_TRACE is not set speeds up the
|
||||
# processing especially on Windows
|
||||
return bool(os.environ.get('COLCON_TRACE'))
|
||||
|
||||
|
||||
def get_commands(pkg_name, prefix, primary_extension, additional_extension):
|
||||
commands = []
|
||||
package_dsv_path = os.path.join(prefix, 'share', pkg_name, 'package.dsv')
|
||||
if os.path.exists(package_dsv_path):
|
||||
commands += process_dsv_file(
|
||||
package_dsv_path, prefix, primary_extension, additional_extension)
|
||||
return commands
|
||||
|
||||
|
||||
def process_dsv_file(
|
||||
dsv_path, prefix, primary_extension=None, additional_extension=None
|
||||
):
|
||||
commands = []
|
||||
if _include_comments():
|
||||
commands.append(FORMAT_STR_COMMENT_LINE.format_map({'comment': dsv_path}))
|
||||
with open(dsv_path, 'r') as h:
|
||||
content = h.read()
|
||||
lines = content.splitlines()
|
||||
|
||||
basenames = OrderedDict()
|
||||
for i, line in enumerate(lines):
|
||||
# skip over empty or whitespace-only lines
|
||||
if not line.strip():
|
||||
continue
|
||||
try:
|
||||
type_, remainder = line.split(';', 1)
|
||||
except ValueError:
|
||||
raise RuntimeError(
|
||||
"Line %d in '%s' doesn't contain a semicolon separating the "
|
||||
'type from the arguments' % (i + 1, dsv_path))
|
||||
if type_ != DSV_TYPE_SOURCE:
|
||||
# handle non-source lines
|
||||
try:
|
||||
commands += handle_dsv_types_except_source(
|
||||
type_, remainder, prefix)
|
||||
except RuntimeError as e:
|
||||
raise RuntimeError(
|
||||
"Line %d in '%s' %s" % (i + 1, dsv_path, e)) from e
|
||||
else:
|
||||
# group remaining source lines by basename
|
||||
path_without_ext, ext = os.path.splitext(remainder)
|
||||
if path_without_ext not in basenames:
|
||||
basenames[path_without_ext] = set()
|
||||
assert ext.startswith('.')
|
||||
ext = ext[1:]
|
||||
if ext in (primary_extension, additional_extension):
|
||||
basenames[path_without_ext].add(ext)
|
||||
|
||||
# add the dsv extension to each basename if the file exists
|
||||
for basename, extensions in basenames.items():
|
||||
if not os.path.isabs(basename):
|
||||
basename = os.path.join(prefix, basename)
|
||||
if os.path.exists(basename + '.dsv'):
|
||||
extensions.add('dsv')
|
||||
|
||||
for basename, extensions in basenames.items():
|
||||
if not os.path.isabs(basename):
|
||||
basename = os.path.join(prefix, basename)
|
||||
if 'dsv' in extensions:
|
||||
# process dsv files recursively
|
||||
commands += process_dsv_file(
|
||||
basename + '.dsv', prefix, primary_extension=primary_extension,
|
||||
additional_extension=additional_extension)
|
||||
elif primary_extension in extensions and len(extensions) == 1:
|
||||
# source primary-only files
|
||||
commands += [
|
||||
FORMAT_STR_INVOKE_SCRIPT.format_map({
|
||||
'prefix': prefix,
|
||||
'script_path': basename + '.' + primary_extension})]
|
||||
elif additional_extension in extensions:
|
||||
# source non-primary files
|
||||
commands += [
|
||||
FORMAT_STR_INVOKE_SCRIPT.format_map({
|
||||
'prefix': prefix,
|
||||
'script_path': basename + '.' + additional_extension})]
|
||||
|
||||
return commands
|
||||
|
||||
|
||||
def handle_dsv_types_except_source(type_, remainder, prefix):
|
||||
commands = []
|
||||
if type_ in (DSV_TYPE_SET, DSV_TYPE_SET_IF_UNSET):
|
||||
try:
|
||||
env_name, value = remainder.split(';', 1)
|
||||
except ValueError:
|
||||
raise RuntimeError(
|
||||
"doesn't contain a semicolon separating the environment name "
|
||||
'from the value')
|
||||
try_prefixed_value = os.path.join(prefix, value) if value else prefix
|
||||
if os.path.exists(try_prefixed_value):
|
||||
value = try_prefixed_value
|
||||
if type_ == DSV_TYPE_SET:
|
||||
commands += _set(env_name, value)
|
||||
elif type_ == DSV_TYPE_SET_IF_UNSET:
|
||||
commands += _set_if_unset(env_name, value)
|
||||
else:
|
||||
assert False
|
||||
elif type_ in (
|
||||
DSV_TYPE_APPEND_NON_DUPLICATE,
|
||||
DSV_TYPE_PREPEND_NON_DUPLICATE,
|
||||
DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS
|
||||
):
|
||||
try:
|
||||
env_name_and_values = remainder.split(';')
|
||||
except ValueError:
|
||||
raise RuntimeError(
|
||||
"doesn't contain a semicolon separating the environment name "
|
||||
'from the values')
|
||||
env_name = env_name_and_values[0]
|
||||
values = env_name_and_values[1:]
|
||||
for value in values:
|
||||
if not value:
|
||||
value = prefix
|
||||
elif not os.path.isabs(value):
|
||||
value = os.path.join(prefix, value)
|
||||
if (
|
||||
type_ == DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS and
|
||||
not os.path.exists(value)
|
||||
):
|
||||
comment = f'skip extending {env_name} with not existing ' \
|
||||
f'path: {value}'
|
||||
if _include_comments():
|
||||
commands.append(
|
||||
FORMAT_STR_COMMENT_LINE.format_map({'comment': comment}))
|
||||
elif type_ == DSV_TYPE_APPEND_NON_DUPLICATE:
|
||||
commands += _append_unique_value(env_name, value)
|
||||
else:
|
||||
commands += _prepend_unique_value(env_name, value)
|
||||
else:
|
||||
raise RuntimeError(
|
||||
'contains an unknown environment hook type: ' + type_)
|
||||
return commands
|
||||
|
||||
|
||||
env_state = {}
|
||||
|
||||
|
||||
def _append_unique_value(name, value):
|
||||
global env_state
|
||||
if name not in env_state:
|
||||
if os.environ.get(name):
|
||||
env_state[name] = set(os.environ[name].split(os.pathsep))
|
||||
else:
|
||||
env_state[name] = set()
|
||||
# append even if the variable has not been set yet, in case a shell script sets the
|
||||
# same variable without the knowledge of this Python script.
|
||||
# later _remove_ending_separators() will cleanup any unintentional leading separator
|
||||
extend = FORMAT_STR_USE_ENV_VAR.format_map({'name': name}) + os.pathsep
|
||||
line = FORMAT_STR_SET_ENV_VAR.format_map(
|
||||
{'name': name, 'value': extend + value})
|
||||
if value not in env_state[name]:
|
||||
env_state[name].add(value)
|
||||
else:
|
||||
if not _include_comments():
|
||||
return []
|
||||
line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line})
|
||||
return [line]
|
||||
|
||||
|
||||
def _prepend_unique_value(name, value):
|
||||
global env_state
|
||||
if name not in env_state:
|
||||
if os.environ.get(name):
|
||||
env_state[name] = set(os.environ[name].split(os.pathsep))
|
||||
else:
|
||||
env_state[name] = set()
|
||||
# prepend even if the variable has not been set yet, in case a shell script sets the
|
||||
# same variable without the knowledge of this Python script.
|
||||
# later _remove_ending_separators() will cleanup any unintentional trailing separator
|
||||
extend = os.pathsep + FORMAT_STR_USE_ENV_VAR.format_map({'name': name})
|
||||
line = FORMAT_STR_SET_ENV_VAR.format_map(
|
||||
{'name': name, 'value': value + extend})
|
||||
if value not in env_state[name]:
|
||||
env_state[name].add(value)
|
||||
else:
|
||||
if not _include_comments():
|
||||
return []
|
||||
line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line})
|
||||
return [line]
|
||||
|
||||
|
||||
# generate commands for removing prepended underscores
|
||||
def _remove_ending_separators():
|
||||
# do nothing if the shell extension does not implement the logic
|
||||
if FORMAT_STR_REMOVE_TRAILING_SEPARATOR is None:
|
||||
return []
|
||||
|
||||
global env_state
|
||||
commands = []
|
||||
for name in env_state:
|
||||
# skip variables that already had values before this script started prepending
|
||||
if name in os.environ:
|
||||
continue
|
||||
commands += [
|
||||
FORMAT_STR_REMOVE_LEADING_SEPARATOR.format_map({'name': name}),
|
||||
FORMAT_STR_REMOVE_TRAILING_SEPARATOR.format_map({'name': name})]
|
||||
return commands
|
||||
|
||||
|
||||
def _set(name, value):
|
||||
global env_state
|
||||
env_state[name] = value
|
||||
line = FORMAT_STR_SET_ENV_VAR.format_map(
|
||||
{'name': name, 'value': value})
|
||||
return [line]
|
||||
|
||||
|
||||
def _set_if_unset(name, value):
|
||||
global env_state
|
||||
line = FORMAT_STR_SET_ENV_VAR.format_map(
|
||||
{'name': name, 'value': value})
|
||||
if env_state.get(name, os.environ.get(name)):
|
||||
line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line})
|
||||
return [line]
|
||||
|
||||
|
||||
if __name__ == '__main__': # pragma: no cover
|
||||
try:
|
||||
rc = main()
|
||||
except RuntimeError as e:
|
||||
print(str(e), file=sys.stderr)
|
||||
rc = 1
|
||||
sys.exit(rc)
|
||||
@@ -1,107 +0,0 @@
|
||||
# generated from colcon_bash/shell/template/prefix.bash.em
|
||||
|
||||
# This script extends the environment with all packages contained in this
|
||||
# prefix path.
|
||||
|
||||
# a bash script is able to determine its own path if necessary
|
||||
if [ -z "$COLCON_CURRENT_PREFIX" ]; then
|
||||
_colcon_prefix_bash_COLCON_CURRENT_PREFIX="$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" > /dev/null && pwd)"
|
||||
else
|
||||
_colcon_prefix_bash_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX"
|
||||
fi
|
||||
|
||||
# function to prepend a value to a variable
|
||||
# which uses colons as separators
|
||||
# duplicates as well as trailing separators are avoided
|
||||
# first argument: the name of the result variable
|
||||
# second argument: the value to be prepended
|
||||
_colcon_prefix_bash_prepend_unique_value() {
|
||||
# arguments
|
||||
_listname="$1"
|
||||
_value="$2"
|
||||
|
||||
# get values from variable
|
||||
eval _values=\"\$$_listname\"
|
||||
# backup the field separator
|
||||
_colcon_prefix_bash_prepend_unique_value_IFS="$IFS"
|
||||
IFS=":"
|
||||
# start with the new value
|
||||
_all_values="$_value"
|
||||
# iterate over existing values in the variable
|
||||
for _item in $_values; do
|
||||
# ignore empty strings
|
||||
if [ -z "$_item" ]; then
|
||||
continue
|
||||
fi
|
||||
# ignore duplicates of _value
|
||||
if [ "$_item" = "$_value" ]; then
|
||||
continue
|
||||
fi
|
||||
# keep non-duplicate values
|
||||
_all_values="$_all_values:$_item"
|
||||
done
|
||||
unset _item
|
||||
# restore the field separator
|
||||
IFS="$_colcon_prefix_bash_prepend_unique_value_IFS"
|
||||
unset _colcon_prefix_bash_prepend_unique_value_IFS
|
||||
# export the updated variable
|
||||
eval export $_listname=\"$_all_values\"
|
||||
unset _all_values
|
||||
unset _values
|
||||
|
||||
unset _value
|
||||
unset _listname
|
||||
}
|
||||
|
||||
# add this prefix to the COLCON_PREFIX_PATH
|
||||
_colcon_prefix_bash_prepend_unique_value COLCON_PREFIX_PATH "$_colcon_prefix_bash_COLCON_CURRENT_PREFIX"
|
||||
unset _colcon_prefix_bash_prepend_unique_value
|
||||
|
||||
# check environment variable for custom Python executable
|
||||
if [ -n "$COLCON_PYTHON_EXECUTABLE" ]; then
|
||||
if [ ! -f "$COLCON_PYTHON_EXECUTABLE" ]; then
|
||||
echo "error: COLCON_PYTHON_EXECUTABLE '$COLCON_PYTHON_EXECUTABLE' doesn't exist"
|
||||
return 1
|
||||
fi
|
||||
_colcon_python_executable="$COLCON_PYTHON_EXECUTABLE"
|
||||
else
|
||||
# try the Python executable known at configure time
|
||||
_colcon_python_executable="/usr/bin/python3"
|
||||
# if it doesn't exist try a fall back
|
||||
if [ ! -f "$_colcon_python_executable" ]; then
|
||||
if ! /usr/bin/env python3 --version > /dev/null 2> /dev/null; then
|
||||
echo "error: unable to find python3 executable"
|
||||
return 1
|
||||
fi
|
||||
_colcon_python_executable=`/usr/bin/env python3 -c "import sys; print(sys.executable)"`
|
||||
fi
|
||||
fi
|
||||
|
||||
# function to source another script with conditional trace output
|
||||
# first argument: the path of the script
|
||||
_colcon_prefix_sh_source_script() {
|
||||
if [ -f "$1" ]; then
|
||||
if [ -n "$COLCON_TRACE" ]; then
|
||||
echo ". \"$1\""
|
||||
fi
|
||||
. "$1"
|
||||
else
|
||||
echo "not found: \"$1\"" 1>&2
|
||||
fi
|
||||
}
|
||||
|
||||
# get all commands in topological order
|
||||
_colcon_ordered_commands="$($_colcon_python_executable "$_colcon_prefix_bash_COLCON_CURRENT_PREFIX/_local_setup_util_sh.py" sh bash)"
|
||||
unset _colcon_python_executable
|
||||
if [ -n "$COLCON_TRACE" ]; then
|
||||
echo "Execute generated script:"
|
||||
echo "<<<"
|
||||
echo "${_colcon_ordered_commands}"
|
||||
echo ">>>"
|
||||
fi
|
||||
eval "${_colcon_ordered_commands}"
|
||||
unset _colcon_ordered_commands
|
||||
|
||||
unset _colcon_prefix_sh_source_script
|
||||
|
||||
unset _colcon_prefix_bash_COLCON_CURRENT_PREFIX
|
||||
@@ -1,55 +0,0 @@
|
||||
# generated from colcon_powershell/shell/template/prefix.ps1.em
|
||||
|
||||
# This script extends the environment with all packages contained in this
|
||||
# prefix path.
|
||||
|
||||
# check environment variable for custom Python executable
|
||||
if ($env:COLCON_PYTHON_EXECUTABLE) {
|
||||
if (!(Test-Path "$env:COLCON_PYTHON_EXECUTABLE" -PathType Leaf)) {
|
||||
echo "error: COLCON_PYTHON_EXECUTABLE '$env:COLCON_PYTHON_EXECUTABLE' doesn't exist"
|
||||
exit 1
|
||||
}
|
||||
$_colcon_python_executable="$env:COLCON_PYTHON_EXECUTABLE"
|
||||
} else {
|
||||
# use the Python executable known at configure time
|
||||
$_colcon_python_executable="/usr/bin/python3"
|
||||
# if it doesn't exist try a fall back
|
||||
if (!(Test-Path "$_colcon_python_executable" -PathType Leaf)) {
|
||||
if (!(Get-Command "python3" -ErrorAction SilentlyContinue)) {
|
||||
echo "error: unable to find python3 executable"
|
||||
exit 1
|
||||
}
|
||||
$_colcon_python_executable="python3"
|
||||
}
|
||||
}
|
||||
|
||||
# function to source another script with conditional trace output
|
||||
# first argument: the path of the script
|
||||
function _colcon_prefix_powershell_source_script {
|
||||
param (
|
||||
$_colcon_prefix_powershell_source_script_param
|
||||
)
|
||||
# source script with conditional trace output
|
||||
if (Test-Path $_colcon_prefix_powershell_source_script_param) {
|
||||
if ($env:COLCON_TRACE) {
|
||||
echo ". '$_colcon_prefix_powershell_source_script_param'"
|
||||
}
|
||||
. "$_colcon_prefix_powershell_source_script_param"
|
||||
} else {
|
||||
Write-Error "not found: '$_colcon_prefix_powershell_source_script_param'"
|
||||
}
|
||||
}
|
||||
|
||||
# get all commands in topological order
|
||||
$_colcon_ordered_commands = & "$_colcon_python_executable" "$(Split-Path $PSCommandPath -Parent)/_local_setup_util_ps1.py" ps1
|
||||
|
||||
# execute all commands in topological order
|
||||
if ($env:COLCON_TRACE) {
|
||||
echo "Execute generated script:"
|
||||
echo "<<<"
|
||||
$_colcon_ordered_commands.Split([Environment]::NewLine, [StringSplitOptions]::RemoveEmptyEntries) | Write-Output
|
||||
echo ">>>"
|
||||
}
|
||||
if ($_colcon_ordered_commands) {
|
||||
$_colcon_ordered_commands.Split([Environment]::NewLine, [StringSplitOptions]::RemoveEmptyEntries) | Invoke-Expression
|
||||
}
|
||||
@@ -1,137 +0,0 @@
|
||||
# generated from colcon_core/shell/template/prefix.sh.em
|
||||
|
||||
# This script extends the environment with all packages contained in this
|
||||
# prefix path.
|
||||
|
||||
# since a plain shell script can't determine its own path when being sourced
|
||||
# either use the provided COLCON_CURRENT_PREFIX
|
||||
# or fall back to the build time prefix (if it exists)
|
||||
_colcon_prefix_sh_COLCON_CURRENT_PREFIX="/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install"
|
||||
if [ -z "$COLCON_CURRENT_PREFIX" ]; then
|
||||
if [ ! -d "$_colcon_prefix_sh_COLCON_CURRENT_PREFIX" ]; then
|
||||
echo "The build time path \"$_colcon_prefix_sh_COLCON_CURRENT_PREFIX\" doesn't exist. Either source a script for a different shell or set the environment variable \"COLCON_CURRENT_PREFIX\" explicitly." 1>&2
|
||||
unset _colcon_prefix_sh_COLCON_CURRENT_PREFIX
|
||||
return 1
|
||||
fi
|
||||
else
|
||||
_colcon_prefix_sh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX"
|
||||
fi
|
||||
|
||||
# function to prepend a value to a variable
|
||||
# which uses colons as separators
|
||||
# duplicates as well as trailing separators are avoided
|
||||
# first argument: the name of the result variable
|
||||
# second argument: the value to be prepended
|
||||
_colcon_prefix_sh_prepend_unique_value() {
|
||||
# arguments
|
||||
_listname="$1"
|
||||
_value="$2"
|
||||
|
||||
# get values from variable
|
||||
eval _values=\"\$$_listname\"
|
||||
# backup the field separator
|
||||
_colcon_prefix_sh_prepend_unique_value_IFS="$IFS"
|
||||
IFS=":"
|
||||
# start with the new value
|
||||
_all_values="$_value"
|
||||
_contained_value=""
|
||||
# iterate over existing values in the variable
|
||||
for _item in $_values; do
|
||||
# ignore empty strings
|
||||
if [ -z "$_item" ]; then
|
||||
continue
|
||||
fi
|
||||
# ignore duplicates of _value
|
||||
if [ "$_item" = "$_value" ]; then
|
||||
_contained_value=1
|
||||
continue
|
||||
fi
|
||||
# keep non-duplicate values
|
||||
_all_values="$_all_values:$_item"
|
||||
done
|
||||
unset _item
|
||||
if [ -z "$_contained_value" ]; then
|
||||
if [ -n "$COLCON_TRACE" ]; then
|
||||
if [ "$_all_values" = "$_value" ]; then
|
||||
echo "export $_listname=$_value"
|
||||
else
|
||||
echo "export $_listname=$_value:\$$_listname"
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
unset _contained_value
|
||||
# restore the field separator
|
||||
IFS="$_colcon_prefix_sh_prepend_unique_value_IFS"
|
||||
unset _colcon_prefix_sh_prepend_unique_value_IFS
|
||||
# export the updated variable
|
||||
eval export $_listname=\"$_all_values\"
|
||||
unset _all_values
|
||||
unset _values
|
||||
|
||||
unset _value
|
||||
unset _listname
|
||||
}
|
||||
|
||||
# add this prefix to the COLCON_PREFIX_PATH
|
||||
_colcon_prefix_sh_prepend_unique_value COLCON_PREFIX_PATH "$_colcon_prefix_sh_COLCON_CURRENT_PREFIX"
|
||||
unset _colcon_prefix_sh_prepend_unique_value
|
||||
|
||||
# check environment variable for custom Python executable
|
||||
if [ -n "$COLCON_PYTHON_EXECUTABLE" ]; then
|
||||
if [ ! -f "$COLCON_PYTHON_EXECUTABLE" ]; then
|
||||
echo "error: COLCON_PYTHON_EXECUTABLE '$COLCON_PYTHON_EXECUTABLE' doesn't exist"
|
||||
return 1
|
||||
fi
|
||||
_colcon_python_executable="$COLCON_PYTHON_EXECUTABLE"
|
||||
else
|
||||
# try the Python executable known at configure time
|
||||
_colcon_python_executable="/usr/bin/python3"
|
||||
# if it doesn't exist try a fall back
|
||||
if [ ! -f "$_colcon_python_executable" ]; then
|
||||
if ! /usr/bin/env python3 --version > /dev/null 2> /dev/null; then
|
||||
echo "error: unable to find python3 executable"
|
||||
return 1
|
||||
fi
|
||||
_colcon_python_executable=`/usr/bin/env python3 -c "import sys; print(sys.executable)"`
|
||||
fi
|
||||
fi
|
||||
|
||||
# function to source another script with conditional trace output
|
||||
# first argument: the path of the script
|
||||
_colcon_prefix_sh_source_script() {
|
||||
if [ -f "$1" ]; then
|
||||
if [ -n "$COLCON_TRACE" ]; then
|
||||
echo "# . \"$1\""
|
||||
fi
|
||||
. "$1"
|
||||
else
|
||||
echo "not found: \"$1\"" 1>&2
|
||||
fi
|
||||
}
|
||||
|
||||
# get all commands in topological order
|
||||
_colcon_ordered_commands="$($_colcon_python_executable "$_colcon_prefix_sh_COLCON_CURRENT_PREFIX/_local_setup_util_sh.py" sh)"
|
||||
unset _colcon_python_executable
|
||||
if [ -n "$COLCON_TRACE" ]; then
|
||||
echo "_colcon_prefix_sh_source_script() {
|
||||
if [ -f \"\$1\" ]; then
|
||||
if [ -n \"\$COLCON_TRACE\" ]; then
|
||||
echo \"# . \\\"\$1\\\"\"
|
||||
fi
|
||||
. \"\$1\"
|
||||
else
|
||||
echo \"not found: \\\"\$1\\\"\" 1>&2
|
||||
fi
|
||||
}"
|
||||
echo "# Execute generated script:"
|
||||
echo "# <<<"
|
||||
echo "${_colcon_ordered_commands}"
|
||||
echo "# >>>"
|
||||
echo "unset _colcon_prefix_sh_source_script"
|
||||
fi
|
||||
eval "${_colcon_ordered_commands}"
|
||||
unset _colcon_ordered_commands
|
||||
|
||||
unset _colcon_prefix_sh_source_script
|
||||
|
||||
unset _colcon_prefix_sh_COLCON_CURRENT_PREFIX
|
||||
@@ -1,120 +0,0 @@
|
||||
# generated from colcon_zsh/shell/template/prefix.zsh.em
|
||||
|
||||
# This script extends the environment with all packages contained in this
|
||||
# prefix path.
|
||||
|
||||
# a zsh script is able to determine its own path if necessary
|
||||
if [ -z "$COLCON_CURRENT_PREFIX" ]; then
|
||||
_colcon_prefix_zsh_COLCON_CURRENT_PREFIX="$(builtin cd -q "`dirname "${(%):-%N}"`" > /dev/null && pwd)"
|
||||
else
|
||||
_colcon_prefix_zsh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX"
|
||||
fi
|
||||
|
||||
# function to convert array-like strings into arrays
|
||||
# to workaround SH_WORD_SPLIT not being set
|
||||
_colcon_prefix_zsh_convert_to_array() {
|
||||
local _listname=$1
|
||||
local _dollar="$"
|
||||
local _split="{="
|
||||
local _to_array="(\"$_dollar$_split$_listname}\")"
|
||||
eval $_listname=$_to_array
|
||||
}
|
||||
|
||||
# function to prepend a value to a variable
|
||||
# which uses colons as separators
|
||||
# duplicates as well as trailing separators are avoided
|
||||
# first argument: the name of the result variable
|
||||
# second argument: the value to be prepended
|
||||
_colcon_prefix_zsh_prepend_unique_value() {
|
||||
# arguments
|
||||
_listname="$1"
|
||||
_value="$2"
|
||||
|
||||
# get values from variable
|
||||
eval _values=\"\$$_listname\"
|
||||
# backup the field separator
|
||||
_colcon_prefix_zsh_prepend_unique_value_IFS="$IFS"
|
||||
IFS=":"
|
||||
# start with the new value
|
||||
_all_values="$_value"
|
||||
# workaround SH_WORD_SPLIT not being set
|
||||
_colcon_prefix_zsh_convert_to_array _values
|
||||
# iterate over existing values in the variable
|
||||
for _item in $_values; do
|
||||
# ignore empty strings
|
||||
if [ -z "$_item" ]; then
|
||||
continue
|
||||
fi
|
||||
# ignore duplicates of _value
|
||||
if [ "$_item" = "$_value" ]; then
|
||||
continue
|
||||
fi
|
||||
# keep non-duplicate values
|
||||
_all_values="$_all_values:$_item"
|
||||
done
|
||||
unset _item
|
||||
# restore the field separator
|
||||
IFS="$_colcon_prefix_zsh_prepend_unique_value_IFS"
|
||||
unset _colcon_prefix_zsh_prepend_unique_value_IFS
|
||||
# export the updated variable
|
||||
eval export $_listname=\"$_all_values\"
|
||||
unset _all_values
|
||||
unset _values
|
||||
|
||||
unset _value
|
||||
unset _listname
|
||||
}
|
||||
|
||||
# add this prefix to the COLCON_PREFIX_PATH
|
||||
_colcon_prefix_zsh_prepend_unique_value COLCON_PREFIX_PATH "$_colcon_prefix_zsh_COLCON_CURRENT_PREFIX"
|
||||
unset _colcon_prefix_zsh_prepend_unique_value
|
||||
unset _colcon_prefix_zsh_convert_to_array
|
||||
|
||||
# check environment variable for custom Python executable
|
||||
if [ -n "$COLCON_PYTHON_EXECUTABLE" ]; then
|
||||
if [ ! -f "$COLCON_PYTHON_EXECUTABLE" ]; then
|
||||
echo "error: COLCON_PYTHON_EXECUTABLE '$COLCON_PYTHON_EXECUTABLE' doesn't exist"
|
||||
return 1
|
||||
fi
|
||||
_colcon_python_executable="$COLCON_PYTHON_EXECUTABLE"
|
||||
else
|
||||
# try the Python executable known at configure time
|
||||
_colcon_python_executable="/usr/bin/python3"
|
||||
# if it doesn't exist try a fall back
|
||||
if [ ! -f "$_colcon_python_executable" ]; then
|
||||
if ! /usr/bin/env python3 --version > /dev/null 2> /dev/null; then
|
||||
echo "error: unable to find python3 executable"
|
||||
return 1
|
||||
fi
|
||||
_colcon_python_executable=`/usr/bin/env python3 -c "import sys; print(sys.executable)"`
|
||||
fi
|
||||
fi
|
||||
|
||||
# function to source another script with conditional trace output
|
||||
# first argument: the path of the script
|
||||
_colcon_prefix_sh_source_script() {
|
||||
if [ -f "$1" ]; then
|
||||
if [ -n "$COLCON_TRACE" ]; then
|
||||
echo ". \"$1\""
|
||||
fi
|
||||
. "$1"
|
||||
else
|
||||
echo "not found: \"$1\"" 1>&2
|
||||
fi
|
||||
}
|
||||
|
||||
# get all commands in topological order
|
||||
_colcon_ordered_commands="$($_colcon_python_executable "$_colcon_prefix_zsh_COLCON_CURRENT_PREFIX/_local_setup_util_sh.py" sh zsh)"
|
||||
unset _colcon_python_executable
|
||||
if [ -n "$COLCON_TRACE" ]; then
|
||||
echo "Execute generated script:"
|
||||
echo "<<<"
|
||||
echo "${_colcon_ordered_commands}"
|
||||
echo ">>>"
|
||||
fi
|
||||
eval "${_colcon_ordered_commands}"
|
||||
unset _colcon_ordered_commands
|
||||
|
||||
unset _colcon_prefix_sh_source_script
|
||||
|
||||
unset _colcon_prefix_zsh_COLCON_CURRENT_PREFIX
|
||||
@@ -1,31 +0,0 @@
|
||||
# generated from colcon_bash/shell/template/prefix_chain.bash.em
|
||||
|
||||
# This script extends the environment with the environment of other prefix
|
||||
# paths which were sourced when this file was generated as well as all packages
|
||||
# contained in this prefix path.
|
||||
|
||||
# function to source another script with conditional trace output
|
||||
# first argument: the path of the script
|
||||
_colcon_prefix_chain_bash_source_script() {
|
||||
if [ -f "$1" ]; then
|
||||
if [ -n "$COLCON_TRACE" ]; then
|
||||
echo ". \"$1\""
|
||||
fi
|
||||
. "$1"
|
||||
else
|
||||
echo "not found: \"$1\"" 1>&2
|
||||
fi
|
||||
}
|
||||
|
||||
# source chained prefixes
|
||||
# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script
|
||||
COLCON_CURRENT_PREFIX="/opt/ros/humble"
|
||||
_colcon_prefix_chain_bash_source_script "$COLCON_CURRENT_PREFIX/local_setup.bash"
|
||||
|
||||
# source this prefix
|
||||
# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script
|
||||
COLCON_CURRENT_PREFIX="$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" > /dev/null && pwd)"
|
||||
_colcon_prefix_chain_bash_source_script "$COLCON_CURRENT_PREFIX/local_setup.bash"
|
||||
|
||||
unset COLCON_CURRENT_PREFIX
|
||||
unset _colcon_prefix_chain_bash_source_script
|
||||
@@ -1,29 +0,0 @@
|
||||
# generated from colcon_powershell/shell/template/prefix_chain.ps1.em
|
||||
|
||||
# This script extends the environment with the environment of other prefix
|
||||
# paths which were sourced when this file was generated as well as all packages
|
||||
# contained in this prefix path.
|
||||
|
||||
# function to source another script with conditional trace output
|
||||
# first argument: the path of the script
|
||||
function _colcon_prefix_chain_powershell_source_script {
|
||||
param (
|
||||
$_colcon_prefix_chain_powershell_source_script_param
|
||||
)
|
||||
# source script with conditional trace output
|
||||
if (Test-Path $_colcon_prefix_chain_powershell_source_script_param) {
|
||||
if ($env:COLCON_TRACE) {
|
||||
echo ". '$_colcon_prefix_chain_powershell_source_script_param'"
|
||||
}
|
||||
. "$_colcon_prefix_chain_powershell_source_script_param"
|
||||
} else {
|
||||
Write-Error "not found: '$_colcon_prefix_chain_powershell_source_script_param'"
|
||||
}
|
||||
}
|
||||
|
||||
# source chained prefixes
|
||||
_colcon_prefix_chain_powershell_source_script "/opt/ros/humble\local_setup.ps1"
|
||||
|
||||
# source this prefix
|
||||
$env:COLCON_CURRENT_PREFIX=(Split-Path $PSCommandPath -Parent)
|
||||
_colcon_prefix_chain_powershell_source_script "$env:COLCON_CURRENT_PREFIX\local_setup.ps1"
|
||||
@@ -1,45 +0,0 @@
|
||||
# generated from colcon_core/shell/template/prefix_chain.sh.em
|
||||
|
||||
# This script extends the environment with the environment of other prefix
|
||||
# paths which were sourced when this file was generated as well as all packages
|
||||
# contained in this prefix path.
|
||||
|
||||
# since a plain shell script can't determine its own path when being sourced
|
||||
# either use the provided COLCON_CURRENT_PREFIX
|
||||
# or fall back to the build time prefix (if it exists)
|
||||
_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX=/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install
|
||||
if [ ! -z "$COLCON_CURRENT_PREFIX" ]; then
|
||||
_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX"
|
||||
elif [ ! -d "$_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX" ]; then
|
||||
echo "The build time path \"$_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX\" doesn't exist. Either source a script for a different shell or set the environment variable \"COLCON_CURRENT_PREFIX\" explicitly." 1>&2
|
||||
unset _colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX
|
||||
return 1
|
||||
fi
|
||||
|
||||
# function to source another script with conditional trace output
|
||||
# first argument: the path of the script
|
||||
_colcon_prefix_chain_sh_source_script() {
|
||||
if [ -f "$1" ]; then
|
||||
if [ -n "$COLCON_TRACE" ]; then
|
||||
echo "# . \"$1\""
|
||||
fi
|
||||
. "$1"
|
||||
else
|
||||
echo "not found: \"$1\"" 1>&2
|
||||
fi
|
||||
}
|
||||
|
||||
# source chained prefixes
|
||||
# setting COLCON_CURRENT_PREFIX avoids relying on the build time prefix of the sourced script
|
||||
COLCON_CURRENT_PREFIX="/opt/ros/humble"
|
||||
_colcon_prefix_chain_sh_source_script "$COLCON_CURRENT_PREFIX/local_setup.sh"
|
||||
|
||||
|
||||
# source this prefix
|
||||
# setting COLCON_CURRENT_PREFIX avoids relying on the build time prefix of the sourced script
|
||||
COLCON_CURRENT_PREFIX="$_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX"
|
||||
_colcon_prefix_chain_sh_source_script "$COLCON_CURRENT_PREFIX/local_setup.sh"
|
||||
|
||||
unset _colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX
|
||||
unset _colcon_prefix_chain_sh_source_script
|
||||
unset COLCON_CURRENT_PREFIX
|
||||
@@ -1,31 +0,0 @@
|
||||
# generated from colcon_zsh/shell/template/prefix_chain.zsh.em
|
||||
|
||||
# This script extends the environment with the environment of other prefix
|
||||
# paths which were sourced when this file was generated as well as all packages
|
||||
# contained in this prefix path.
|
||||
|
||||
# function to source another script with conditional trace output
|
||||
# first argument: the path of the script
|
||||
_colcon_prefix_chain_zsh_source_script() {
|
||||
if [ -f "$1" ]; then
|
||||
if [ -n "$COLCON_TRACE" ]; then
|
||||
echo ". \"$1\""
|
||||
fi
|
||||
. "$1"
|
||||
else
|
||||
echo "not found: \"$1\"" 1>&2
|
||||
fi
|
||||
}
|
||||
|
||||
# source chained prefixes
|
||||
# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script
|
||||
COLCON_CURRENT_PREFIX="/opt/ros/humble"
|
||||
_colcon_prefix_chain_zsh_source_script "$COLCON_CURRENT_PREFIX/local_setup.zsh"
|
||||
|
||||
# source this prefix
|
||||
# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script
|
||||
COLCON_CURRENT_PREFIX="$(builtin cd -q "`dirname "${(%):-%N}"`" > /dev/null && pwd)"
|
||||
_colcon_prefix_chain_zsh_source_script "$COLCON_CURRENT_PREFIX/local_setup.zsh"
|
||||
|
||||
unset COLCON_CURRENT_PREFIX
|
||||
unset _colcon_prefix_chain_zsh_source_script
|
||||
@@ -1,2 +0,0 @@
|
||||
[0.000000] (-) TimerEvent: {}
|
||||
[0.000528] (-) EventReactorShutdown: {}
|
||||
@@ -1,62 +0,0 @@
|
||||
[0.774s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
|
||||
[0.774s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, verb_parser=<colcon_defaults.argument_parser.defaults.DefaultArgumentsDecorator object at 0x7f6f676af490>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0x7f6f67ef8a00>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0x7f6f67ef8a00>>)
|
||||
[0.848s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
|
||||
[0.849s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
|
||||
[0.849s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
|
||||
[0.849s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
|
||||
[0.849s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
|
||||
[0.849s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
|
||||
[0.849s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src'
|
||||
[0.849s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.849s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
|
||||
[0.849s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
|
||||
[0.849s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
|
||||
[0.850s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
|
||||
[0.850s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
|
||||
[0.850s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
|
||||
[0.850s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
|
||||
[0.850s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
|
||||
[0.873s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
|
||||
[0.873s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.873s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
|
||||
[0.873s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
|
||||
[0.873s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
|
||||
[0.873s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
|
||||
[0.873s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
|
||||
[0.873s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
|
||||
[0.873s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
|
||||
[0.917s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
|
||||
[0.917s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
|
||||
[0.924s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 271 installed packages in /opt/ros/humble
|
||||
[0.927s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
|
||||
[1.053s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
|
||||
[1.058s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
|
||||
[1.058s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
|
||||
[1.059s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
|
||||
[1.059s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
|
||||
[1.059s] DEBUG:colcon.colcon_core.event_reactor:joining thread
|
||||
[1.068s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
|
||||
[1.068s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
|
||||
[1.068s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
|
||||
[1.102s] DEBUG:colcon.colcon_core.event_reactor:joined thread
|
||||
[1.114s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
|
||||
[1.115s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/local_setup.ps1'
|
||||
[1.117s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/_local_setup_util_ps1.py'
|
||||
[1.118s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/setup.ps1'
|
||||
[1.121s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/local_setup.sh'
|
||||
[1.121s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/_local_setup_util_sh.py'
|
||||
[1.122s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/setup.sh'
|
||||
[1.124s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/local_setup.bash'
|
||||
[1.124s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/setup.bash'
|
||||
[1.126s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/local_setup.zsh'
|
||||
[1.126s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/setup.zsh'
|
||||
@@ -1,2 +0,0 @@
|
||||
[0.000000] (-) TimerEvent: {}
|
||||
[0.000528] (-) EventReactorShutdown: {}
|
||||
@@ -1,62 +0,0 @@
|
||||
[0.774s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
|
||||
[0.774s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, verb_parser=<colcon_defaults.argument_parser.defaults.DefaultArgumentsDecorator object at 0x7f6f676af490>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0x7f6f67ef8a00>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0x7f6f67ef8a00>>)
|
||||
[0.848s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
|
||||
[0.849s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
|
||||
[0.849s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
|
||||
[0.849s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
|
||||
[0.849s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
|
||||
[0.849s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
|
||||
[0.849s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src'
|
||||
[0.849s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.849s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
|
||||
[0.849s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
|
||||
[0.849s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
|
||||
[0.850s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
|
||||
[0.850s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
|
||||
[0.850s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
|
||||
[0.850s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
|
||||
[0.850s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
|
||||
[0.873s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
|
||||
[0.873s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.873s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
|
||||
[0.873s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
|
||||
[0.873s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
|
||||
[0.873s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
|
||||
[0.873s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
|
||||
[0.873s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
|
||||
[0.873s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
|
||||
[0.917s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
|
||||
[0.917s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
|
||||
[0.924s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 271 installed packages in /opt/ros/humble
|
||||
[0.927s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
|
||||
[1.053s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
|
||||
[1.058s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
|
||||
[1.058s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
|
||||
[1.059s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
|
||||
[1.059s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
|
||||
[1.059s] DEBUG:colcon.colcon_core.event_reactor:joining thread
|
||||
[1.068s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
|
||||
[1.068s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
|
||||
[1.068s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
|
||||
[1.102s] DEBUG:colcon.colcon_core.event_reactor:joined thread
|
||||
[1.114s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
|
||||
[1.115s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/local_setup.ps1'
|
||||
[1.117s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/_local_setup_util_ps1.py'
|
||||
[1.118s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/setup.ps1'
|
||||
[1.121s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/local_setup.sh'
|
||||
[1.121s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/_local_setup_util_sh.py'
|
||||
[1.122s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/setup.sh'
|
||||
[1.124s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/local_setup.bash'
|
||||
[1.124s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/setup.bash'
|
||||
[1.126s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/local_setup.zsh'
|
||||
[1.126s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/setup.zsh'
|
||||
@@ -1,2 +0,0 @@
|
||||
[0.000000] (-) TimerEvent: {}
|
||||
[0.000528] (-) EventReactorShutdown: {}
|
||||
@@ -1,62 +0,0 @@
|
||||
[0.774s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
|
||||
[0.774s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, verb_parser=<colcon_defaults.argument_parser.defaults.DefaultArgumentsDecorator object at 0x7f6f676af490>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0x7f6f67ef8a00>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0x7f6f67ef8a00>>)
|
||||
[0.848s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
|
||||
[0.849s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
|
||||
[0.849s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
|
||||
[0.849s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
|
||||
[0.849s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
|
||||
[0.849s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
|
||||
[0.849s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src'
|
||||
[0.849s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.849s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
|
||||
[0.849s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
|
||||
[0.849s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
|
||||
[0.850s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
|
||||
[0.850s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
|
||||
[0.850s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
|
||||
[0.850s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
|
||||
[0.850s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.872s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
|
||||
[0.873s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
|
||||
[0.873s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
|
||||
[0.873s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
|
||||
[0.873s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
|
||||
[0.873s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
|
||||
[0.873s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
|
||||
[0.873s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
|
||||
[0.873s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
|
||||
[0.873s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
|
||||
[0.917s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
|
||||
[0.917s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
|
||||
[0.924s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 271 installed packages in /opt/ros/humble
|
||||
[0.927s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
|
||||
[1.053s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
|
||||
[1.058s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
|
||||
[1.058s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
|
||||
[1.059s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
|
||||
[1.059s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
|
||||
[1.059s] DEBUG:colcon.colcon_core.event_reactor:joining thread
|
||||
[1.068s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
|
||||
[1.068s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
|
||||
[1.068s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
|
||||
[1.102s] DEBUG:colcon.colcon_core.event_reactor:joined thread
|
||||
[1.114s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
|
||||
[1.115s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/local_setup.ps1'
|
||||
[1.117s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/_local_setup_util_ps1.py'
|
||||
[1.118s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/setup.ps1'
|
||||
[1.121s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/local_setup.sh'
|
||||
[1.121s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/_local_setup_util_sh.py'
|
||||
[1.122s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/setup.sh'
|
||||
[1.124s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/local_setup.bash'
|
||||
[1.124s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/setup.bash'
|
||||
[1.126s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/local_setup.zsh'
|
||||
[1.126s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/rosi2/ros2_driver/src/ti_mmwave_rospkg/src/install/setup.zsh'
|
||||
@@ -14,7 +14,7 @@
|
||||
/*Include ROS specific headers*/
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
#include "std_msgs/msg/string.hpp"
|
||||
#include "serial/serial.h"
|
||||
#include "serial/serial.h"
|
||||
#include "pluginlib/class_list_macros.hpp"
|
||||
|
||||
/*mmWave Driver Headers*/
|
||||
@@ -26,43 +26,43 @@ using namespace std::chrono_literals;
|
||||
std::shared_ptr<rclcpp::Node> nodeptr2 = nullptr;
|
||||
|
||||
class mmWaveCommSrv : public rclcpp::Node
|
||||
{
|
||||
{
|
||||
public:
|
||||
|
||||
mmWaveCommSrv() : Node("mmWaveCommSrv")
|
||||
{
|
||||
this->declare_parameter("command_port", rclcpp::PARAMETER_STRING);
|
||||
this->declare_parameter("command_rate", rclcpp::PARAMETER_STRING);
|
||||
this->declare_parameter("data_port", rclcpp::PARAMETER_STRING);
|
||||
this->declare_parameter("data_rate", rclcpp::PARAMETER_STRING);
|
||||
this->declare_parameter("max_allowed_elevation_angle_deg", rclcpp::PARAMETER_STRING);
|
||||
this->declare_parameter("max_allowed_azimuth_angle_deg", rclcpp::PARAMETER_STRING);
|
||||
this->declare_parameter("frame_id", rclcpp::PARAMETER_STRING);
|
||||
this->declare_parameter("mmwavecli_name", rclcpp::PARAMETER_STRING);
|
||||
this->declare_parameter("/ti_mmwave/radar_scan_pcl", rclcpp::PARAMETER_STRING);
|
||||
// this->declare_parameter("data_port", rclcpp::PARAMETER_STRING);
|
||||
// this->declare_parameter("data_rate", rclcpp::PARAMETER_STRING);
|
||||
// this->declare_parameter("max_allowed_elevation_angle_deg", rclcpp::PARAMETER_STRING);
|
||||
// this->declare_parameter("max_allowed_azimuth_angle_deg", rclcpp::PARAMETER_STRING);
|
||||
// this->declare_parameter("frame_id", rclcpp::PARAMETER_STRING);
|
||||
// this->declare_parameter("mmwavecli_name", rclcpp::PARAMETER_STRING);
|
||||
// this->declare_parameter("/ti_mmwave/radar_scan_pcl", rclcpp::PARAMETER_STRING);
|
||||
|
||||
}
|
||||
private:
|
||||
|
||||
};
|
||||
|
||||
void handle_service_request(const std::shared_ptr<ti_mmwave_rospkg_msgs::srv::MmwaveCli::Request> request,
|
||||
void handle_service_request(const std::shared_ptr<ti_mmwave_rospkg_msgs::srv::MmwaveCli::Request> request,
|
||||
const std::shared_ptr<ti_mmwave_rospkg_msgs::srv::MmwaveCli::Response> response)
|
||||
{
|
||||
|
||||
std::string mySerialPort = nodeptr2->get_parameter("command_port").as_string();
|
||||
std::string myBaudRate = nodeptr2->get_parameter("command_rate").as_string();
|
||||
std::string mmWaveCLIName = nodeptr2->get_parameter("mmwavecli_name").as_string();
|
||||
// std::string mmWaveCLIName = nodeptr2->get_parameter("mmwavecli_name").as_string();
|
||||
std::string sensorStart = "sensorStart\n";
|
||||
|
||||
/*Open Serial port and error check*/
|
||||
serial::Serial mySerialObject("", std::stoi(myBaudRate), serial::Timeout::simpleTimeout(1000));
|
||||
mySerialObject.setPort(mySerialPort.c_str());
|
||||
try
|
||||
try
|
||||
{
|
||||
mySerialObject.open();
|
||||
}
|
||||
catch (std::exception &e1)
|
||||
}
|
||||
catch (std::exception &e1)
|
||||
{
|
||||
RCLCPP_ERROR(rclcpp::get_logger("rclcpp"),"\n\n\nmmWaveCommSrv: Failed to open User serial port with error: %s\n\n", e1.what());
|
||||
RCLCPP_ERROR(rclcpp::get_logger("rclcpp"),"\n\n\nmmWaveCommSrv: Power cycle the mmWave Sensor with the reset button while keeping the USB connected. Ensure the correct launch and configuration files are being used. Close all nodes, wait 10 Seconds, then relaunch the driver\n\n");
|
||||
@@ -72,7 +72,7 @@ void handle_service_request(const std::shared_ptr<ti_mmwave_rospkg_msgs::srv::Mm
|
||||
|
||||
/*Read any previous pending response(s)*/
|
||||
while (mySerialObject.available() > 0)
|
||||
{
|
||||
{
|
||||
mySerialObject.readline(response->resp, 1024, ":/>");
|
||||
//RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"mmWaveCommSrv: Received (previous) response from sensor: '%s'", response->resp.c_str());
|
||||
response->resp = "";
|
||||
@@ -92,7 +92,7 @@ void handle_service_request(const std::shared_ptr<ti_mmwave_rospkg_msgs::srv::Mm
|
||||
if(!sensorStart.compare(request->comm))
|
||||
{
|
||||
rclcpp::shutdown();
|
||||
exit(0);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
@@ -38,7 +38,7 @@ int main(int argc, char **argv) {
|
||||
rclcpp::Client<ti_mmwave_rospkg_msgs::srv::MmwaveCli>::SharedPtr client = nodeptr->create_client<ti_mmwave_rospkg_msgs::srv::MmwaveCli>("/ti_mmwave_rospkg_msgs/mmwave_cli");
|
||||
auto request = std::make_shared<ti_mmwave_rospkg_msgs::srv::MmwaveCli::Request>();
|
||||
auto response = std::make_shared<ti_mmwave_rospkg_msgs::srv::MmwaveCli::Response>();
|
||||
std::string mmWaveCLIname = nodeptr->get_parameter("mmwavecli_name").as_string();
|
||||
// std::string mmWaveCLIname = nodeptr->get_parameter("mmwavecli_name").as_string();
|
||||
std::string mmWaveCLIcfg = nodeptr->get_parameter("mmwavecli_cfg").as_string();
|
||||
std::string sensorStart = "sensorStart";
|
||||
|
||||
|
||||
@@ -9,14 +9,10 @@ project(ti_mmwave_rospkg_msgs)
|
||||
## dependencies
|
||||
|
||||
find_package(ament_cmake REQUIRED)
|
||||
|
||||
find_package(rosidl_default_generators REQUIRED)
|
||||
|
||||
find_package(rclcpp REQUIRED)
|
||||
|
||||
find_package(std_msgs REQUIRED)
|
||||
|
||||
|
||||
## Generate messages in the 'msg' folder
|
||||
set(msg_files
|
||||
"msg/RadarScan.msg"
|
||||
@@ -33,14 +29,9 @@ set(srv_files
|
||||
rosidl_generate_interfaces(ti_mmwave_rospkg_msgs
|
||||
${msg_files}
|
||||
${srv_files}
|
||||
DEPENDENCIES std_msgs
|
||||
)
|
||||
|
||||
## ament_target_dependencies(std_msgs rclcpp)
|
||||
|
||||
ament_export_dependencies(
|
||||
rosidl_default_runtime
|
||||
std_msgs
|
||||
rclcpp
|
||||
)
|
||||
ament_export_dependencies(rosidl_default_runtime)
|
||||
|
||||
ament_package()
|
||||
@@ -1,4 +1,2 @@
|
||||
uint32 seq
|
||||
uint32 stamp
|
||||
string frame_id
|
||||
std_msgs/Header header
|
||||
uint32 state
|
||||
@@ -1,3 +1,2 @@
|
||||
string frame_id
|
||||
uint32 stamp
|
||||
uint8 tid
|
||||
std_msgs/Header header
|
||||
uint8 tid
|
||||
|
||||
@@ -1,6 +1,4 @@
|
||||
uint32 seq
|
||||
uint32 stamp
|
||||
string frame_id
|
||||
std_msgs/Header header
|
||||
uint16 point_id
|
||||
float32 x
|
||||
float32 y
|
||||
|
||||
@@ -1,4 +1,3 @@
|
||||
string frame_id
|
||||
uint32 stamp
|
||||
std_msgs/Header header
|
||||
uint32 num_tracks
|
||||
RadarTrackContents[] track
|
||||
|
||||
@@ -1,5 +1,4 @@
|
||||
string frame_id
|
||||
uint32 stamp
|
||||
std_msgs/Header header
|
||||
uint32 tid
|
||||
float32 posx
|
||||
float32 posy
|
||||
|
||||
Reference in New Issue
Block a user