What are the three main categories of path planning?
Grid based
Sampling based
Optimization based
Represent the map as a grid, search through the grid for a path
Randomly sample points to find a path
These algorithms interpret path planning as an optimization / controls problem
Find best controls u that minimizes cost function
A ROS bag file is used to store multiple topic's message data.
rosbag play <your bagfile>
-l
:rosbag play <your bagfile> -l
[Space]
in the terminal running the bag file in order to pause/play the recording. roscore
before playing the bag file!rviz
for visualization of the world in previous exercises, now we
are going to use rqt_image_view
for displaying images.rqt_gui
with rosrun rqt_gui rqt_gui
to allow for multiple panescv::Mat
is the datatype used to describe images in OpenCVSince a picture is in 2D, with rows and columns, we can use a 2D matrix to model this:
To model this using a matrix, instead of a 2D matrix, we now have a 3D matrix, with each entry having a row,
column, and now also a channel:
cv::Mat M(2, 2, CV_8UC1, cv::Scalar(255));
std::cout << "M = " << std::endl << " " << M << std::endl;
M =
[255, 255;
255, 255]
.at<type>(row, column)
method:cv::Mat M(2, 2, CV_8UC1, cv::Scalar(255));
M.at<uchar>(0, 1) = 5;
M.at<uchar>(1, 0) = 9;
std::cout << "M = " << std::endl << " " << M << std::endl;
M =
[255,
5;
9, 255]
uchar
as the template argument for .at
CV_8UC1
8U
: 8 bitsC1
: 1 channel, ie. greyscale imagesCV_8UC3
insteadSubscribing to images is a bit different than other message types
sensor_msgs::Image
(raw)sensor_msgs::CompressedImage
(compressed)theora_image_transport/Packet
(theora)Using image_transport
will convert all these types to sensor_msgs::Image
for us:
void imageCallback(sensor_msgs::Image& image) {}
// ...
image_transport::ImageTransport it{nh};
image_transport::Subscriber image_sub
= it.subscribe("/out", 1, imageCallback, {"compressed"});
cv::Mat
, but rather sensor_msgs::Image
.sensor_msgs::Image
and cv::Mat
, we need to use cv_bridge
:// For OpenCV
#include <opencv2/opencv.hpp>
// For cv_bridge
#include <cv_bridge/cv_bridge.h>
void img_callback(const sensor_msgs::ImageConstPtr &msg)
{
cv_bridge::CvImagePtr cv_ptr = cv_bridge::toCvCopy(msg, "bgr8");
cv::Mat frame = cv_ptr->image;
}
sensor_msgs::Image
sensor_msgs::ImageConstPtr
If you look at the declaration of sensor_msgs::ImageConstPtr
(Ctrl-B, or Ctrl-click), you'll see this:
typedef boost::shared_ptr< ::sensor_msgs::Image const> ImageConstPtr;
Don't worry about the typedef
. You can think of the above line as equivalent to the following:
using ImageConstPtr = boost::shared_ptr<sensor_msgs::Image const>;
So, basically ImageConstPtr
is just an alias for boost::shared_ptr<sensor_msgs::Image const>
.
It turns out that ROS will automatically add "~Ptr" and "~ConstPtr" aliases for each message type that you define for convenience. But why?
Smart Pointers allow you to manage a resource without copying it around
shared_ptr
: multiple owners of a resource without copying it aroundDon't copy around the sensor_msgs::Image
, but instead get a shared_ptr
pointing to the resource
Important for large objects like images or pointclouds because copying is expensive.
Now, let's say we've just done some image processing, and we want to publish our processed image
Need to convert our cv::Mat
back to a sensor_msgs::Image
To do that, we first need to create a cv_bridge::CvImage
, and set its image
member to the cv::Mat
:
cv::Mat mat;
// Some processing done on mat
cv_bridge::CvImage cv_image;
cv_image.image = mat;
cv_ptr->encoding = "mono8"; // mono8 for BINARY (CV_8UC1), bgr8 COLORED (CV_8UC3)
Afterwards, we can call the toImageMsg()
method to get a sensor_msgs::Image
which we can publish:
g_img_pub.publish(cv_ptr.toImageMsg();
The most simple type of kernel is an identity kernel:
For now, the least you need to know about kernels is that are used by many computer vision algorithms and many CV functions will simply require you to declare the kernel size (usually around 3 to 9).
cv::getStructingElement
allows you to create kernels of common shapes
cv::Mat kernel(int x, int y)
{
return cv::getStructuringElement(cv::MORPH_RECT, cv::Size(x, y));
}
Motivation
cv::GaussianBlur(frame, frame, cv::Size(3,3), 0, 0)
Very useful and convenient when doing filtering by color
The way to convert an BGR image to HSV is by doing:
cv::cvtColor(frame, hsv_frame, cv::COLOR_BGR2HSV);
cv::inRange()
-For example, if we wanted to color threshold for blue/green:
cv::inRange(hsv_frame, cv::Scalar(20, 120, 120), cv::Scalar(100, 255, 255), green_found);
![]() |
![]() |
![]() |
---|---|---|
Original | Erode | Dilate |
![]() |
![]() |
---|---|
Opening | Closing |
List of points that represents the edge of a shape.
Useful tool for shape analysis and object detection and recognition.
Useful features for a contour
rqt_image_viewer
. /camera/image
and write a callback function taking in a sensor_msgs::ImageConstPtr
./event/race_started
of type std_msgs::Bool
for if the race has begunGood luck!
We learnt about:
rqt_image_view
See you next week!