Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix: cherry pick hotfix PRs for beta v0.1.0 #7

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 0 additions & 3 deletions common/web_controller/launch/web_controller.launch.xml
Original file line number Diff line number Diff line change
@@ -1,8 +1,5 @@
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<!-- Web Controller -->

<executable cmd="python3 -m http.server 8085" cwd="$(find-pkg-share web_controller)/www" name="web_server"/>
<node pkg="rosbridge_server" exec="rosbridge_websocket" name="rosbridge_server_node">
</node>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -149,7 +149,7 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node
PointCloud2::SharedPtr & out);
void publish();

void removeRADTFields(
void convertToXYZICloud(
const sensor_msgs::msg::PointCloud2 & input_cloud,
sensor_msgs::msg::PointCloud2 & output_cloud);
void setPeriod(const int64_t new_period);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -298,26 +298,13 @@ void PointCloudConcatenateDataSynchronizerComponent::publish()

///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////

void PointCloudConcatenateDataSynchronizerComponent::removeRADTFields(
void PointCloudConcatenateDataSynchronizerComponent::convertToXYZICloud(
const sensor_msgs::msg::PointCloud2 & input_cloud, sensor_msgs::msg::PointCloud2 & output_cloud)
{
bool has_intensity = std::any_of(
input_cloud.fields.begin(), input_cloud.fields.end(),
[](auto & field) { return field.name == "intensity"; });

if (input_cloud.fields.size() == 3 || (input_cloud.fields.size() == 4 && has_intensity)) {
output_cloud = input_cloud;
} else if (has_intensity) {
pcl::PointCloud<PointXYZI> tmp_cloud;
pcl::fromROSMsg(input_cloud, tmp_cloud);
pcl::toROSMsg(tmp_cloud, output_cloud);
output_cloud.header = input_cloud.header;
} else {
pcl::PointCloud<pcl::PointXYZ> tmp_cloud;
pcl::fromROSMsg(input_cloud, tmp_cloud);
pcl::toROSMsg(tmp_cloud, output_cloud);
output_cloud.header = input_cloud.header;
}
pcl::PointCloud<PointXYZI> tmp_cloud;
pcl::fromROSMsg(input_cloud, tmp_cloud);
pcl::toROSMsg(tmp_cloud, output_cloud);
output_cloud.header = input_cloud.header;
}

void PointCloudConcatenateDataSynchronizerComponent::setPeriod(const int64_t new_period)
Expand All @@ -342,7 +329,7 @@ void PointCloudConcatenateDataSynchronizerComponent::cloud_callback(
std::lock_guard<std::mutex> lock(mutex_);

sensor_msgs::msg::PointCloud2 xyz_cloud;
removeRADTFields(*input_ptr, xyz_cloud);
convertToXYZICloud(*input_ptr, xyz_cloud);
sensor_msgs::msg::PointCloud2::ConstSharedPtr xyz_input_ptr(
new sensor_msgs::msg::PointCloud2(xyz_cloud));

Expand Down