Skip to content

Commit

Permalink
subscribe to trigger if CanTrigger is true
Browse files Browse the repository at this point in the history
  • Loading branch information
scpeters committed Apr 19, 2018
1 parent b595d4a commit 23d995b
Show file tree
Hide file tree
Showing 4 changed files with 24 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -210,7 +210,10 @@ namespace gazebo
private: event::EventT<void()> load_event_;

// make a trigger function that the child classes can override
// and a function that returns bool to indicate whether the trigger
// should be used
protected: virtual void TriggerCamera();
protected: virtual bool CanTriggerCamera();
private: void TriggerCameraInternal(const std_msgs::Empty::ConstPtr &dummy);
private: ros::Subscriber trigger_subscriber_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,8 @@ namespace gazebo

protected: virtual void TriggerCamera();

protected: virtual bool CanTriggerCamera();

protected: event::ConnectionPtr preRenderConnection_;

public: void SetCameraEnabled(const bool _enabled);
Expand Down
20 changes: 14 additions & 6 deletions gazebo_plugins/src/gazebo_ros_camera_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -350,12 +350,15 @@ void GazeboRosCameraUtils::LoadThread()
this->cameraUpdateRateSubscriber_ = this->rosnode_->subscribe(rate_so);
*/

ros::SubscribeOptions trigger_so =
ros::SubscribeOptions::create<std_msgs::Empty>(
this->trigger_topic_name_, 1,
boost::bind(&GazeboRosCameraUtils::TriggerCameraInternal, this, _1),
ros::VoidPtr(), &this->camera_queue_);
this->trigger_subscriber_ = this->rosnode_->subscribe(trigger_so);
if (this->CanTriggerCamera())
{
ros::SubscribeOptions trigger_so =
ros::SubscribeOptions::create<std_msgs::Empty>(
this->trigger_topic_name_, 1,
boost::bind(&GazeboRosCameraUtils::TriggerCameraInternal, this, _1),
ros::VoidPtr(), &this->camera_queue_);
this->trigger_subscriber_ = this->rosnode_->subscribe(trigger_so);
}

this->Init();
}
Expand All @@ -364,6 +367,11 @@ void GazeboRosCameraUtils::TriggerCamera()
{
}

bool GazeboRosCameraUtils::CanTriggerCamera()
{
return false;
}

void GazeboRosCameraUtils::TriggerCameraInternal(
const std_msgs::Empty::ConstPtr &dummy)
{
Expand Down
5 changes: 5 additions & 0 deletions gazebo_plugins/src/gazebo_ros_triggered_camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,6 +107,11 @@ void GazeboRosTriggeredCamera::TriggerCamera()
this->triggered = true;
}

bool GazeboRosTriggeredCamera::CanTriggerCamera()
{
return true;
}

void GazeboRosTriggeredCamera::PreRender()
{
std::lock_guard<std::mutex> lock(this->mutex);
Expand Down

0 comments on commit 23d995b

Please sign in to comment.