Skip to content

Commit

Permalink
changes to avoid deprecated API's (#399)
Browse files Browse the repository at this point in the history
Signed-off-by: William Woodall <william@osrfoundation.org>
  • Loading branch information
wjwwood authored May 8, 2019
1 parent f99800c commit cb2fb54
Show file tree
Hide file tree
Showing 27 changed files with 47 additions and 32 deletions.
7 changes: 5 additions & 2 deletions rviz_common/include/rviz_common/ros_topic_display.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -183,12 +183,15 @@ class RosTopicDisplay : public _RosTopicDisplay
}

try {
// TODO(wjwwood): update this class to use rclcpp::QoS.
auto qos = rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile));
qos.get_rmw_qos_profile() = qos_profile;
// TODO(anhosi,wjwwood): replace with abstraction for subscriptions once available
subscription_ =
rviz_ros_node_.lock()->get_raw_node()->template create_subscription<MessageType>(
topic_property_->getTopicStd(),
[this](const typename MessageType::ConstSharedPtr message) {incomingMessage(message);},
qos_profile);
qos,
[this](const typename MessageType::ConstSharedPtr message) {incomingMessage(message);});
setStatus(properties::StatusProperty::Ok, "Topic", "OK");
} catch (rclcpp::exceptions::InvalidTopicNameError & e) {
setStatus(properties::StatusProperty::Error, "Topic",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -279,16 +279,19 @@ void CameraDisplay::subscribe()
void CameraDisplay::createCameraInfoSubscription()
{
try {
// TODO(wjwwood): update this class to use rclcpp::QoS.
auto qos = rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile));
qos.get_rmw_qos_profile() = qos_profile;
// TODO(anhosi,wjwwood): replace with abstraction for subscriptions one available
caminfo_sub_ = rviz_ros_node_.lock()->get_raw_node()->
template create_subscription<sensor_msgs::msg::CameraInfo>(
topic_property_->getTopicStd() + "/camera_info",
qos,
[this](sensor_msgs::msg::CameraInfo::ConstSharedPtr msg) {
std::unique_lock<std::mutex> lock(caminfo_mutex_);
current_caminfo_ = msg;
new_caminfo_ = true;
},
qos_profile);
});
setStatus(StatusLevel::Ok, CAM_INFO_STATUS, "OK");
} catch (rclcpp::exceptions::InvalidTopicNameError & e) {
setStatus(StatusLevel::Error, CAM_INFO_STATUS, QString("Error subscribing: ") + e.what());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -187,13 +187,16 @@ void MapDisplay::subscribe()
RTDClass::subscribe();

try {
// TODO(wjwwood): update this class to use rclcpp::QoS.
auto qos = rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile));
qos.get_rmw_qos_profile() = qos_profile;
update_subscription_ = rviz_ros_node_.lock()->get_raw_node()->
template create_subscription<map_msgs::msg::OccupancyGridUpdate>(
topic_property_->getTopicStd() + "_updates",
qos,
[this](const map_msgs::msg::OccupancyGridUpdate::ConstSharedPtr message) {
incomingUpdate(message);
},
qos_profile);
});
setStatus(rviz_common::properties::StatusProperty::Ok, "Update Topic", "OK");
} catch (rclcpp::exceptions::InvalidTopicNameError & e) {
setStatus(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,14 +74,17 @@ void MarkerDisplay::subscribe()
void MarkerDisplay::createMarkerArraySubscription()
{
try {
// TODO(wjwwood): update this class to use rclcpp::QoS.
auto qos = rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos_profile));
qos.get_rmw_qos_profile() = qos_profile;
// TODO(anhosi,wjwwood): replace with abstraction for subscriptions one available
array_sub_ = rviz_ros_node_.lock()->get_raw_node()->
template create_subscription<visualization_msgs::msg::MarkerArray>(
topic_property_->getTopicStd() + "_array",
qos,
[this](visualization_msgs::msg::MarkerArray::ConstSharedPtr msg) {
marker_common_->addMessage(msg);
},
qos_profile);
});
setStatus(StatusLevel::Ok, "Array Topic", "OK");
} catch (rclcpp::exceptions::InvalidTopicNameError & e) {
setStatus(StatusLevel::Error, "Array Topic", QString("Error subscribing: ") + e.what());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ void GoalTool::updateTopic()
{
// TODO(anhosi, wjwwood): replace with abstraction for publishers once available
publisher_ = context_->getRosNodeAbstraction().lock()->get_raw_node()->
template create_publisher<geometry_msgs::msg::PoseStamped>(topic_property_->getStdString());
template create_publisher<geometry_msgs::msg::PoseStamped>(topic_property_->getStdString(), 10);
}

void GoalTool::onPoseSet(double x, double y, double theta)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,9 @@ void PointTool::updateTopic()
{
// TODO(anhosi, wjwwood): replace with abstraction for publishers once available
publisher_ = context_->getRosNodeAbstraction().lock()->get_raw_node()->
template create_publisher<geometry_msgs::msg::PointStamped>(topic_property_->getStdString());
template create_publisher<geometry_msgs::msg::PointStamped>(
topic_property_->getStdString(),
10);
}

void PointTool::updateAutoDeactivate() {}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ void InitialPoseTool::updateTopic()
// TODO(anhosi, wjwwood): replace with abstraction for publishers once available
publisher_ = context_->getRosNodeAbstraction().lock()->get_raw_node()->
template create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>(
topic_property_->getStdString());
topic_property_->getStdString(), 10);
}

void InitialPoseTool::onPoseSet(double x, double y, double theta)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ class CameraInfoPublisher : public rclcpp::Node
CameraInfoPublisher()
: Node("camera_info_publisher")
{
publisher = this->create_publisher<sensor_msgs::msg::CameraInfo>("/image/camera_info");
publisher = this->create_publisher<sensor_msgs::msg::CameraInfo>("/image/camera_info", 10);
timer = this->create_wall_timer(500ms, std::bind(&CameraInfoPublisher::timer_callback, this));
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ class FluidPressurePublisher : public rclcpp::Node
FluidPressurePublisher::FluidPressurePublisher()
: Node("fluid_pressure_publisher"), fluid_pressure_(0.)
{
publisher_ = this->create_publisher<sensor_msgs::msg::FluidPressure>("fluid_pressure");
publisher_ = this->create_publisher<sensor_msgs::msg::FluidPressure>("fluid_pressure", 10);

auto timer_callback =
[this]() -> void {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ class GridCellsPublisher : public rclcpp::Node
GridCellsPublisher()
: Node("grid_cells_publisher")
{
publisher = this->create_publisher<nav_msgs::msg::GridCells>("grid_cells");
publisher = this->create_publisher<nav_msgs::msg::GridCells>("grid_cells", 10);
timer = this->create_wall_timer(500ms, std::bind(&GridCellsPublisher::timer_callback, this));
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ class IlluminancePublisher : public rclcpp::Node
IlluminancePublisher::IlluminancePublisher()
: Node("illuminance_publisher"), illuminance_(0.)
{
publisher_ = this->create_publisher<sensor_msgs::msg::Illuminance>("illuminance");
publisher_ = this->create_publisher<sensor_msgs::msg::Illuminance>("illuminance", 10);

auto timer_callback =
[this]() -> void {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ class ImagePublisher : public rclcpp::Node
ImagePublisher()
: Node("image_publisher")
{
publisher = this->create_publisher<sensor_msgs::msg::Image>("image");
publisher = this->create_publisher<sensor_msgs::msg::Image>("image", 10);
timer = this->create_wall_timer(100ms, std::bind(&ImagePublisher::timer_callback, this));
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ class LaserScanPublisher : public rclcpp::Node
timer_(nullptr),
publisher_(nullptr)
{
publisher_ = this->create_publisher<sensor_msgs::msg::LaserScan>("laser_scan");
publisher_ = this->create_publisher<sensor_msgs::msg::LaserScan>("laser_scan", 10);
timer_ = this->create_wall_timer(500ms, std::bind(&LaserScanPublisher::timer_callback, this));
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ class MapPublisher : public rclcpp::Node
MapPublisher()
: Node("map_publisher")
{
publisher = this->create_publisher<nav_msgs::msg::OccupancyGrid>("map");
publisher = this->create_publisher<nav_msgs::msg::OccupancyGrid>("map", 10);
timer = this->create_wall_timer(500ms, std::bind(&MapPublisher::timer_callback, this));
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,8 @@ class MarkerArrayPublisher : public MarkerPublisher
MarkerArrayPublisher()
: MarkerPublisher("marker_array_publisher")
{
array_publisher_ = this->create_publisher<visualization_msgs::msg::MarkerArray>("marker_array");
array_publisher_ =
this->create_publisher<visualization_msgs::msg::MarkerArray>("marker_array", 10);
}

private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ class MarkerPublisher : public rclcpp::Node
MarkerPublisher()
: Node("marker_publisher")
{
publisher_ = this->create_publisher<visualization_msgs::msg::Marker>("marker");
publisher_ = this->create_publisher<visualization_msgs::msg::Marker>("marker", 10);
timer_ = this->create_wall_timer(200ms, std::bind(&MarkerPublisher::timer_callback, this));
}

Expand All @@ -65,7 +65,7 @@ class MarkerPublisher : public rclcpp::Node
: Node(node_name)
{
timer_ = this->create_wall_timer(200ms, std::bind(&MarkerPublisher::timer_callback, this));
publisher_ = this->create_publisher<visualization_msgs::msg::Marker>("marker");
publisher_ = this->create_publisher<visualization_msgs::msg::Marker>("marker", 10);
}

protected:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ class OdometryPublisher : public rclcpp::Node
OdometryPublisher()
: Node("odometry_publisher")
{
publisher = this->create_publisher<nav_msgs::msg::Odometry>("odometry");
publisher = this->create_publisher<nav_msgs::msg::Odometry>("odometry", 10);
timer = this->create_wall_timer(200ms, std::bind(&OdometryPublisher::timer_callback, this));
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ class PathPublisher : public rclcpp::Node
PathPublisher()
: Node("path_publisher")
{
publisher = this->create_publisher<nav_msgs::msg::Path>("path");
publisher = this->create_publisher<nav_msgs::msg::Path>("path", 10);
timer = this->create_wall_timer(500ms, std::bind(&PathPublisher::timer_callback, this));
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ class PointCloud2Publisher : public rclcpp::Node
timer_(nullptr),
publisher_(nullptr)
{
publisher_ = this->create_publisher<sensor_msgs::msg::PointCloud2>("pointcloud2");
publisher_ = this->create_publisher<sensor_msgs::msg::PointCloud2>("pointcloud2", 10);
timer_ = this->create_wall_timer(500ms, std::bind(&PointCloud2Publisher::timer_callback, this));
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ class PointCloudPublisher : public rclcpp::Node
publisher_(nullptr),
points_(points)
{
publisher_ = this->create_publisher<sensor_msgs::msg::PointCloud>("pointcloud");
publisher_ = this->create_publisher<sensor_msgs::msg::PointCloud>("pointcloud", 10);
timer_ = this->create_wall_timer(500ms, std::bind(&PointCloudPublisher::timer_callback, this));
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ class PointStampedPublisher : public rclcpp::Node
PointStampedPublisher()
: Node("point_publisher")
{
publisher = this->create_publisher<geometry_msgs::msg::PointStamped>("point");
publisher = this->create_publisher<geometry_msgs::msg::PointStamped>("point", 10);
timer = this->create_wall_timer(
500ms, std::bind(&PointStampedPublisher::timer_callback, this));
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ class PoseArrayPublisher : public rclcpp::Node
PoseArrayPublisher()
: Node("pose_array_publisher")
{
publisher = this->create_publisher<geometry_msgs::msg::PoseArray>("pose_array");
publisher = this->create_publisher<geometry_msgs::msg::PoseArray>("pose_array", 10);
timer = this->create_wall_timer(500ms, std::bind(&PoseArrayPublisher::timer_callback, this));
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ class PosePublisher : public rclcpp::Node
PosePublisher()
: Node("pose_publisher")
{
publisher = this->create_publisher<geometry_msgs::msg::PoseStamped>("pose");
publisher = this->create_publisher<geometry_msgs::msg::PoseStamped>("pose", 10);
timer = this->create_wall_timer(500ms, std::bind(&PosePublisher::timer_callback, this));
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ class RangePublisher : public rclcpp::Node
RangePublisher()
: Node("range_publisher")
{
publisher = this->create_publisher<sensor_msgs::msg::Range>("range");
publisher = this->create_publisher<sensor_msgs::msg::Range>("range", 10);
timer = this->create_wall_timer(500ms, std::bind(&RangePublisher::timer_callback, this));
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ class RelativeHumidityPublisher : public rclcpp::Node
RelativeHumidityPublisher::RelativeHumidityPublisher()
: Node("relative_humidity_publisher"), relative_humidity_(0.)
{
publisher_ = this->create_publisher<sensor_msgs::msg::RelativeHumidity>("relative_humidity");
publisher_ = this->create_publisher<sensor_msgs::msg::RelativeHumidity>("relative_humidity", 10);

auto timer_callback =
[this]() -> void {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ class SingleMarkerPublisher : public rclcpp::Node
SingleMarkerPublisher()
: Node("marker_publisher")
{
publisher = this->create_publisher<visualization_msgs::msg::Marker>("marker");
publisher = this->create_publisher<visualization_msgs::msg::Marker>("marker", 10);
timer = this->create_wall_timer(200ms, std::bind(&SingleMarkerPublisher::timer_callback, this));
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ class TemperaturePublisher : public rclcpp::Node
TemperaturePublisher::TemperaturePublisher()
: Node("temperature_publisher"), temperature_(0.)
{
publisher_ = this->create_publisher<sensor_msgs::msg::Temperature>("temperature");
publisher_ = this->create_publisher<sensor_msgs::msg::Temperature>("temperature", 10);

auto timer_callback =
[this]() -> void {
Expand Down

0 comments on commit cb2fb54

Please sign in to comment.