18 #include <opencv/highgui.h> 21 #include <sensor_msgs/Image.h> 24 #include <mrpt/version.h> 25 #if MRPT_VERSION>=0x199 26 using namespace mrpt::img;
41 bool ros2mrpt(
const sensor_msgs::Image &msg, CObservationImage &obj)
44 if (!frame1)
return false;
45 IplImage ipl = frame1->
image;
46 obj.image.loadFromIplImage(&ipl);
56 CImage temp_img = obj.image;
57 Mat cvImg = cv::cvarrToMat(temp_img.getAs<IplImage>());
60 sensor_msgs::Image img_msg;
65 msg.encoding =
"bgr8";
66 msg.header = msg_header;
67 msg.height = (int) obj.image.getHeight();
68 msg.width = (int) obj.image.getWidth();
bool mrpt2ros(const CObservationGPS &obj, const std_msgs::Header &msg_header, sensor_msgs::NavSatFix &msg)
File includes methods for converting CNetworkOfPoses*DInf <=> NetworkOfPoses message types...
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
sensor_msgs::ImagePtr toImageMsg() const
bool ros2mrpt(const sensor_msgs::NavSatFix &msg, CObservationGPS &obj)