Compare commits

..

No commits in common. "e0d20a50491756acbc0c6e76a505e611236e2115" and "26e182a855f4d3830b4d0be020d5df6f5c427acb" have entirely different histories.

7 changed files with 14 additions and 52 deletions

3
.gitignore vendored
View File

@ -51,6 +51,3 @@ qtcreator-*
# Catkin custom files # Catkin custom files
CATKIN_IGNORE CATKIN_IGNORE
*.code-workspace
.uploaded

View File

@ -2,15 +2,15 @@ FROM athackst/ros2:foxy-dev
# ** [Optional] Uncomment this section to install additional packages. ** # ** [Optional] Uncomment this section to install additional packages. **
# #
ENV DEBIAN_FRONTEND=noninteractive # ENV DEBIAN_FRONTEND=noninteractive
RUN apt-get update \ # RUN apt-get update \
&& apt-get -y install --no-install-recommends rsync \ # && apt-get -y install --no-install-recommends <your-package-list-here> \
# # #
# Clean up # # Clean up
&& apt-get autoremove -y \ # && apt-get autoremove -y \
&& apt-get clean -y \ # && apt-get clean -y \
&& rm -rf /var/lib/apt/lists/* # && rm -rf /var/lib/apt/lists/*
ENV DEBIAN_FRONTEND=dialog # ENV DEBIAN_FRONTEND=dialog
# Set up auto-source of workspace for ros user # Set up auto-source of workspace for ros user

View File

@ -1,20 +0,0 @@
.PHONY: build run upload
SOURCES := $(wildcard src/ros2aria/src/*.cpp)
HEADERS := $(wildcard src/ros2aria/src/*.hpp)
build/ros2aria/ros2aria: $(SOURCES) $(HEADERS)
colcon build
build: build/ros2aria/ros2aria
.uploaded: build/ros2aria/ros2aria
rsync -r build/ros2aria/ros2aria lab1_5@pionier6:~/ros2aria
touch .uploaded
upload: .uploaded
run: upload
ssh lab1_5@pionier6 -t -- docker run --rm --network=host -it --device /dev/ttyS0 -v /home/lab1_5:/ws irth7/ros2aria-dev /ws/ros2aria

View File

@ -6,5 +6,4 @@ void Ros2Aria::publish()
rclcpp::Time t = robot->getClock()->now(); rclcpp::Time t = robot->getClock()->now();
sensor_msgs::msg::PointCloud sonarData = handleSonar(t); sensor_msgs::msg::PointCloud sonarData = handleSonar(t);
publishSonar(sonarData); publishSonar(sonarData);
publishSonarPointCloud2(sonarData);
} }

View File

@ -15,7 +15,6 @@ Ros2Aria::Ros2Aria()
stop_service_ = this->create_service<std_srvs::srv::Empty>("stop", std::bind(&Ros2Aria::stop, this, _1, _2)); stop_service_ = this->create_service<std_srvs::srv::Empty>("stop", std::bind(&Ros2Aria::stop, this, _1, _2));
sonar_pub_ = this->create_publisher<sensor_msgs::msg::PointCloud>("sonar", 10); sonar_pub_ = this->create_publisher<sensor_msgs::msg::PointCloud>("sonar", 10);
sonar_pointcloud2_pub_ = this->create_publisher<sensor_msgs::msg::PointCloud2>("sonar_pointcloud2", 10);
// listen to sensors // listen to sensors
auto r = robot->getRobot(); auto r = robot->getRobot();

View File

@ -2,7 +2,6 @@
#include "Aria/Aria.h" #include "Aria/Aria.h"
#include "sensor_msgs/msg/point_cloud.hpp" #include "sensor_msgs/msg/point_cloud.hpp"
#include "sensor_msgs/msg/point_cloud2.hpp"
#include "geometry_msgs/msg/twist.hpp" #include "geometry_msgs/msg/twist.hpp"
#include "std_srvs/srv/empty.hpp" #include "std_srvs/srv/empty.hpp"
@ -26,11 +25,8 @@ private:
void publish(); void publish();
rclcpp::Publisher<sensor_msgs::msg::PointCloud>::SharedPtr sonar_pub_; rclcpp::Publisher<sensor_msgs::msg::PointCloud>::SharedPtr sonar_pub_;
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr sonar_pointcloud2_pub_;
sensor_msgs::msg::PointCloud handleSonar(rclcpp::Time stamp); sensor_msgs::msg::PointCloud handleSonar(rclcpp::Time stamp);
void publishSonar(sensor_msgs::msg::PointCloud cloud); void publishSonar(sensor_msgs::msg::PointCloud cloud);
void publishSonarPointCloud2(sensor_msgs::msg::PointCloud cloud);
// subscribers // subscribers
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr cmd_vel_sub_; rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr cmd_vel_sub_;

View File

@ -1,7 +1,5 @@
#include "ros2aria.hpp" #include "ros2aria.hpp"
#include "sensor_msgs/point_cloud_conversion.hpp"
sensor_msgs::msg::PointCloud Ros2Aria::handleSonar(rclcpp::Time stamp) sensor_msgs::msg::PointCloud Ros2Aria::handleSonar(rclcpp::Time stamp)
{ {
sensor_msgs::msg::PointCloud cloud; //sonar readings. sensor_msgs::msg::PointCloud cloud; //sonar readings.
@ -22,12 +20,14 @@ sensor_msgs::msg::PointCloud Ros2Aria::handleSonar(rclcpp::Time stamp)
} }
// getRange() will return an integer between 0 and 5000 (5m) // getRange() will return an integer between 0 and 5000 (5m)
std::cout << reading->getRange() << " ";
// local (x,y). Appears to be from the centre of the robot, since values may // local (x,y). Appears to be from the centre of the robot, since values may
// exceed 5000. This is good, since it means we only need 1 transform. // exceed 5000. This is good, since it means we only need 1 transform.
// x & y seem to be swapped though, i.e. if the robot is driving north // x & y seem to be swapped though, i.e. if the robot is driving north
// x is north/south and y is east/west. // x is north/south and y is east/west.
// //
//ArPose sensor = reading->getSensorPosition(); //position sensor. //ArPose sensor = reading->getSensorPosition(); //position of sensor.
// sonar_debug_info << "(" << reading->getLocalX() // sonar_debug_info << "(" << reading->getLocalX()
// << ", " << reading->getLocalY() // << ", " << reading->getLocalY()
// << ") from (" << sensor.getX() << ", " // << ") from (" << sensor.getX() << ", "
@ -47,16 +47,7 @@ void Ros2Aria::publishSonar(sensor_msgs::msg::PointCloud cloud)
if (this->sonar_pub_->get_subscription_count() == 0) if (this->sonar_pub_->get_subscription_count() == 0)
return; return;
RCLCPP_INFO(this->get_logger(), "publishing sonar pointcloud");
this->sonar_pub_->publish(cloud); this->sonar_pub_->publish(cloud);
}
void Ros2Aria::publishSonarPointCloud2(sensor_msgs::msg::PointCloud cloud)
{
if (this->sonar_pointcloud2_pub_->get_subscription_count() == 0)
return;
sensor_msgs::msg::PointCloud2 cloud2;
sensor_msgs::convertPointCloudToPointCloud2(cloud, cloud2);
this->sonar_pointcloud2_pub_->publish(cloud2);
} }