Skip to content

Commit

Permalink
downsampler -> throttle
Browse files Browse the repository at this point in the history
  • Loading branch information
klaxalk committed Oct 17, 2024
1 parent 17a77ad commit 394590e
Show file tree
Hide file tree
Showing 4 changed files with 27 additions and 28 deletions.
12 changes: 6 additions & 6 deletions mrs_camera_republisher/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ set(CATKIN_DEPENDENCIES

set(LIBRARIES
MrsCameraRepublisher_FrameIdChanger
MrsCameraRepublisher_Downsampler
MrsCameraRepublisher_Throttle
)

find_package(catkin REQUIRED COMPONENTS
Expand Down Expand Up @@ -55,18 +55,18 @@ target_link_libraries(MrsCameraRepublisher_FrameIdChanger
${catkin_LIBRARIES}
)

# Downsampler
# Throttle

add_library(MrsCameraRepublisher_Downsampler
src/downsampler.cpp
add_library(MrsCameraRepublisher_Throttle
src/throttle.cpp
)

add_dependencies(MrsCameraRepublisher_Downsampler
add_dependencies(MrsCameraRepublisher_Throttle
${catkin_EXPORTED_TARGETS}
${${PROJECT_NAME}_EXPORTED_TARGETS}
)

target_link_libraries(MrsCameraRepublisher_Downsampler
target_link_libraries(MrsCameraRepublisher_Throttle
${catkin_LIBRARIES}
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,9 @@
<arg name="original_topic" default="" />
<arg name="new_topic" default="" />

<arg name="camera_name" default="" />
<arg name="camera_name" default="cam" />

<arg name="rate" default="" />
<arg name="rate" default="5.0" />

<arg name="nodelet_manager_name" default="$(optenv nodelet_manager_name)" />

Expand All @@ -18,8 +18,7 @@

<group ns="$(arg UAV_NAME)">

<!-- camera republisher -->
<node pkg="nodelet" type="nodelet" name="downsampler_$(arg camera_name)" args="$(arg nodelet) mrs_camera_republisher/Downsampler $(arg nodelet_manager)" output="screen">
<node pkg="nodelet" type="nodelet" name="throttle_$(arg camera_name)" args="$(arg nodelet) mrs_camera_republisher/Throttle $(arg nodelet_manager)" output="screen">

<param name="rate" value="$(arg rate)" />

Expand Down
6 changes: 3 additions & 3 deletions mrs_camera_republisher/nodelets.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@
</class>
</library>

<library path="lib/libMrsCameraRepublisher_Downsampler">
<class name="mrs_camera_republisher/Downsampler" type="mrs_camera_republisher::Downsampler" base_class_type="nodelet::Nodelet">
<description>Downsampler nodelet</description>
<library path="lib/libMrsCameraRepublisher_Throttle">
<class name="mrs_camera_republisher/Throttle" type="mrs_camera_republisher::Throttle" base_class_type="nodelet::Nodelet">
<description>Camera Throttle nodelet</description>
</class>
</library>
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,9 @@
namespace mrs_camera_republisher
{

/* class Downsampler //{ */
/* class Throttle //{ */

class Downsampler : public nodelet::Nodelet {
class Throttle : public nodelet::Nodelet {

public:
virtual void onInit();
Expand Down Expand Up @@ -53,30 +53,30 @@ class Downsampler : public nodelet::Nodelet {

/* onInit() //{ */

void Downsampler::onInit() {
void Throttle::onInit() {

ros::NodeHandle nh = nodelet::Nodelet::getMTPrivateNodeHandle();

ROS_INFO("[Downsampler]: initializing");
ROS_INFO("[Throttle]: initializing");

ros::Time::waitForValid();

last_time_published_image_ = ros::Time(0);
last_time_published_cam_info_ = ros::Time(0);

mrs_lib::ParamLoader param_loader(nh, "Downsampler");
mrs_lib::ParamLoader param_loader(nh, "Throttle");

double rate;

param_loader.loadParam("rate", rate);

if (!param_loader.loadedSuccessfully()) {
ROS_ERROR("[Downsampler]: failed to load non-optional parameters!");
ROS_ERROR("[Throttle]: failed to load non-optional parameters!");
ros::shutdown();
}

if (rate < 1e-3) {
ROS_ERROR("[Downsampler]: provided rate is too low");
ROS_ERROR("[Throttle]: provided rate is too low");
ros::shutdown();
}

Expand All @@ -88,7 +88,7 @@ void Downsampler::onInit() {

// | ----------------------- subscribers ---------------------- |

subscriber_image_ = it.subscribe("image_in", 1, &Downsampler::callbackImage, this);
subscriber_image_ = it.subscribe("image_in", 1, &Throttle::callbackImage, this);

mrs_lib::SubscribeHandlerOptions shopts;
shopts.nh = nh;
Expand All @@ -99,7 +99,7 @@ void Downsampler::onInit() {
shopts.queue_size = 10;
shopts.transport_hints = ros::TransportHints().tcpNoDelay();

sh_camera_info_ = mrs_lib::SubscribeHandler<sensor_msgs::CameraInfo>(shopts, "camera_info_in", &Downsampler::callbackCameraInfo, this);
sh_camera_info_ = mrs_lib::SubscribeHandler<sensor_msgs::CameraInfo>(shopts, "camera_info_in", &Throttle::callbackCameraInfo, this);

// | ----------------------- publishers ----------------------- |

Expand All @@ -111,7 +111,7 @@ void Downsampler::onInit() {

is_initialized_ = true;

ROS_INFO_ONCE("[Downsampler]: initialized");
ROS_INFO_ONCE("[Throttle]: initialized");
}

//}
Expand All @@ -120,7 +120,7 @@ void Downsampler::onInit() {

/* callbackImage() //{ */

void Downsampler::callbackImage(const sensor_msgs::Image::ConstPtr& msg) {
void Throttle::callbackImage(const sensor_msgs::Image::ConstPtr& msg) {

if (!is_initialized_) {
return;
Expand All @@ -140,14 +140,14 @@ void Downsampler::callbackImage(const sensor_msgs::Image::ConstPtr& msg) {

last_time_published_image_ = ros::Time::now();

ROS_INFO_ONCE("[Downsampler]: republishing downsampled images");
ROS_INFO_ONCE("[Throttle]: republishing throttled images");
}

//}

/* callbackCameraInfo() //{ */

void Downsampler::callbackCameraInfo(const sensor_msgs::CameraInfo::ConstPtr msg) {
void Throttle::callbackCameraInfo(const sensor_msgs::CameraInfo::ConstPtr msg) {

if (!is_initialized_) {
return;
Expand All @@ -167,12 +167,12 @@ void Downsampler::callbackCameraInfo(const sensor_msgs::CameraInfo::ConstPtr msg

last_time_published_cam_info_ = ros::Time::now();

ROS_INFO_ONCE("[Downsampler]: republishing downsampled camera info");
ROS_INFO_ONCE("[Throttle]: republishing throttled camera info");
}

//}

} // namespace mrs_camera_republisher

#include <pluginlib/class_list_macros.h>
PLUGINLIB_EXPORT_CLASS(mrs_camera_republisher::Downsampler, nodelet::Nodelet);
PLUGINLIB_EXPORT_CLASS(mrs_camera_republisher::Throttle, nodelet::Nodelet);

0 comments on commit 394590e

Please sign in to comment.