Rename gray topic
This commit is contained in:
parent
14988ffd24
commit
9a465b9f04
|
@ -13,8 +13,8 @@
|
||||||
<arg name="depth_topic" default="depth/image_raw" />
|
<arg name="depth_topic" default="depth/image_raw" />
|
||||||
<arg name="points_topic" default="points/data_raw" />
|
<arg name="points_topic" default="points/data_raw" />
|
||||||
|
|
||||||
<arg name="left_gray_topic" default="left/image_gray" />
|
<arg name="left_mono_topic" default="left/image_mono" />
|
||||||
<arg name="right_gray_topic" default="right/image_gray" />
|
<arg name="right_mono_topic" default="right/image_mono" />
|
||||||
|
|
||||||
<arg name="imu_topic" default="imu/data_raw" />
|
<arg name="imu_topic" default="imu/data_raw" />
|
||||||
<arg name="temp_topic" default="temp/data_raw" />
|
<arg name="temp_topic" default="temp/data_raw" />
|
||||||
|
@ -105,8 +105,8 @@
|
||||||
<param name="points_topic" value="$(arg points_topic)" />
|
<param name="points_topic" value="$(arg points_topic)" />
|
||||||
<param name="depth_topic" value="$(arg depth_topic)" />
|
<param name="depth_topic" value="$(arg depth_topic)" />
|
||||||
|
|
||||||
<param name="left_gray_topic" value="$(arg left_gray_topic)" />
|
<param name="left_mono_topic" value="$(arg left_mono_topic)" />
|
||||||
<param name="right_gray_topic" value="$(arg right_gray_topic)" />
|
<param name="right_mono_topic" value="$(arg right_mono_topic)" />
|
||||||
|
|
||||||
<param name="imu_topic" value="$(arg imu_topic)" />
|
<param name="imu_topic" value="$(arg imu_topic)" />
|
||||||
<param name="temp_topic" value="$(arg temp_topic)" />
|
<param name="temp_topic" value="$(arg temp_topic)" />
|
||||||
|
|
|
@ -82,11 +82,11 @@ Visualization Manager:
|
||||||
Displays:
|
Displays:
|
||||||
- Class: rviz/Image
|
- Class: rviz/Image
|
||||||
Enabled: true
|
Enabled: true
|
||||||
Image Topic: /mynteye/left/image_gray
|
Image Topic: /mynteye/left/image_mono
|
||||||
Max Value: 1
|
Max Value: 1
|
||||||
Median window: 5
|
Median window: 5
|
||||||
Min Value: 0
|
Min Value: 0
|
||||||
Name: LeftGray
|
Name: LeftMono
|
||||||
Normalize Range: true
|
Normalize Range: true
|
||||||
Queue Size: 2
|
Queue Size: 2
|
||||||
Transport Hint: raw
|
Transport Hint: raw
|
||||||
|
@ -94,18 +94,18 @@ Visualization Manager:
|
||||||
Value: true
|
Value: true
|
||||||
- Class: rviz/Image
|
- Class: rviz/Image
|
||||||
Enabled: true
|
Enabled: true
|
||||||
Image Topic: /mynteye/right/image_gray
|
Image Topic: /mynteye/right/image_mono
|
||||||
Max Value: 1
|
Max Value: 1
|
||||||
Median window: 5
|
Median window: 5
|
||||||
Min Value: 0
|
Min Value: 0
|
||||||
Name: RightGray
|
Name: RightMono
|
||||||
Normalize Range: true
|
Normalize Range: true
|
||||||
Queue Size: 2
|
Queue Size: 2
|
||||||
Transport Hint: raw
|
Transport Hint: raw
|
||||||
Unreliable: false
|
Unreliable: false
|
||||||
Value: true
|
Value: true
|
||||||
Enabled: false
|
Enabled: true
|
||||||
Name: Gray
|
Name: Mono
|
||||||
- Class: rviz/Group
|
- Class: rviz/Group
|
||||||
Displays:
|
Displays:
|
||||||
- Class: rviz/Image
|
- Class: rviz/Image
|
||||||
|
|
|
@ -115,13 +115,13 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||||
private_nh_.getParam(it->second + "_topic", stream_topics[it->first]);
|
private_nh_.getParam(it->second + "_topic", stream_topics[it->first]);
|
||||||
}
|
}
|
||||||
|
|
||||||
std::map<Stream, std::string> gray_names{{Stream::LEFT, "left_gray"},
|
std::map<Stream, std::string> mono_names{{Stream::LEFT, "left_mono"},
|
||||||
{Stream::RIGHT, "right_gray"}};
|
{Stream::RIGHT, "right_mono"}};
|
||||||
|
|
||||||
std::map<Stream, std::string> gray_topics{};
|
std::map<Stream, std::string> mono_topics{};
|
||||||
for (auto &&it = gray_names.begin(); it != gray_names.end(); ++it) {
|
for (auto &&it = mono_names.begin(); it != mono_names.end(); ++it) {
|
||||||
gray_topics[it->first] = it->second;
|
mono_topics[it->first] = it->second;
|
||||||
private_nh_.getParam(it->second + "_topic", gray_topics[it->first]);
|
private_nh_.getParam(it->second + "_topic", mono_topics[it->first]);
|
||||||
}
|
}
|
||||||
|
|
||||||
std::string imu_topic = "imu";
|
std::string imu_topic = "imu";
|
||||||
|
@ -188,10 +188,10 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||||
NODELET_INFO_STREAM("Advertized on topic " << topic);
|
NODELET_INFO_STREAM("Advertized on topic " << topic);
|
||||||
}
|
}
|
||||||
|
|
||||||
for (auto &&it = gray_topics.begin(); it != gray_topics.end(); ++it) {
|
for (auto &&it = mono_topics.begin(); it != mono_topics.end(); ++it) {
|
||||||
auto &&topic = gray_topics[it->first];
|
auto &&topic = mono_topics[it->first];
|
||||||
if (it->first == Stream::LEFT || it->first == Stream::RIGHT) { // camera
|
if (it->first == Stream::LEFT || it->first == Stream::RIGHT) { // camera
|
||||||
gray_publishers_[it->first] = it_mynteye.advertiseCamera(topic, 1);
|
mono_publishers_[it->first] = it_mynteye.advertiseCamera(topic, 1);
|
||||||
}
|
}
|
||||||
NODELET_INFO_STREAM("Advertized on topic " << topic);
|
NODELET_INFO_STREAM("Advertized on topic " << topic);
|
||||||
}
|
}
|
||||||
|
@ -291,7 +291,7 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||||
|
|
||||||
++left_count_;
|
++left_count_;
|
||||||
publishCamera(Stream::LEFT, data, left_count_, stamp);
|
publishCamera(Stream::LEFT, data, left_count_, stamp);
|
||||||
publishGray(Stream::LEFT, data, left_count_, stamp);
|
publishMono(Stream::LEFT, data, left_count_, stamp);
|
||||||
NODELET_DEBUG_STREAM(
|
NODELET_DEBUG_STREAM(
|
||||||
Stream::LEFT << ", count: " << left_count_
|
Stream::LEFT << ", count: " << left_count_
|
||||||
<< ", frame_id: " << data.img->frame_id
|
<< ", frame_id: " << data.img->frame_id
|
||||||
|
@ -305,7 +305,7 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||||
|
|
||||||
++right_count_;
|
++right_count_;
|
||||||
publishCamera(Stream::RIGHT, data, right_count_, stamp);
|
publishCamera(Stream::RIGHT, data, right_count_, stamp);
|
||||||
publishGray(Stream::RIGHT, data, right_count_, stamp);
|
publishMono(Stream::RIGHT, data, right_count_, stamp);
|
||||||
NODELET_DEBUG_STREAM(
|
NODELET_DEBUG_STREAM(
|
||||||
Stream::RIGHT << ", count: " << right_count_
|
Stream::RIGHT << ", count: " << right_count_
|
||||||
<< ", frame_id: " << data.img->frame_id
|
<< ", frame_id: " << data.img->frame_id
|
||||||
|
@ -419,21 +419,21 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||||
image_publishers_[stream].publish(msg);
|
image_publishers_[stream].publish(msg);
|
||||||
}
|
}
|
||||||
|
|
||||||
void publishGray(
|
void publishMono(
|
||||||
const Stream &stream, const api::StreamData &data, std::uint32_t seq,
|
const Stream &stream, const api::StreamData &data, std::uint32_t seq,
|
||||||
ros::Time stamp) {
|
ros::Time stamp) {
|
||||||
if (gray_publishers_[stream].getNumSubscribers() == 0)
|
if (mono_publishers_[stream].getNumSubscribers() == 0)
|
||||||
return;
|
return;
|
||||||
std_msgs::Header header;
|
std_msgs::Header header;
|
||||||
header.seq = seq;
|
header.seq = seq;
|
||||||
header.stamp = stamp;
|
header.stamp = stamp;
|
||||||
header.frame_id = frame_ids_[stream];
|
header.frame_id = frame_ids_[stream];
|
||||||
cv::Mat gray;
|
cv::Mat mono;
|
||||||
cv::cvtColor(data.frame, gray, CV_RGB2GRAY);
|
cv::cvtColor(data.frame, mono, CV_RGB2GRAY);
|
||||||
auto &&msg = cv_bridge::CvImage(header, enc::MONO8, gray).toImageMsg();
|
auto &&msg = cv_bridge::CvImage(header, enc::MONO8, mono).toImageMsg();
|
||||||
auto &&info = getCameraInfo(stream);
|
auto &&info = getCameraInfo(stream);
|
||||||
info->header.stamp = msg->header.stamp;
|
info->header.stamp = msg->header.stamp;
|
||||||
gray_publishers_[stream].publish(msg, info);
|
mono_publishers_[stream].publish(msg, info);
|
||||||
}
|
}
|
||||||
|
|
||||||
void publishPoints(
|
void publishPoints(
|
||||||
|
@ -878,8 +878,8 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||||
std::map<Stream, image_transport::Publisher> image_publishers_;
|
std::map<Stream, image_transport::Publisher> image_publishers_;
|
||||||
std::map<Stream, std::string> image_encodings_;
|
std::map<Stream, std::string> image_encodings_;
|
||||||
|
|
||||||
// gray: LEFT, RIGHT
|
// mono: LEFT, RIGHT
|
||||||
std::map<Stream, image_transport::CameraPublisher> gray_publishers_;
|
std::map<Stream, image_transport::CameraPublisher> mono_publishers_;
|
||||||
|
|
||||||
// pointcloud: POINTS
|
// pointcloud: POINTS
|
||||||
ros::Publisher points_publisher_;
|
ros::Publisher points_publisher_;
|
||||||
|
|
Loading…
Reference in New Issue
Block a user