Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include <gazebo_plugins/vision_reconfigure.h>
00036
00037 VisionReconfigure::VisionReconfigure() : nh_("")
00038 {
00039 this->nh_.setCallbackQueue(&this->queue_);
00040
00041
00042 this->callback_queue_thread_ = boost::thread( boost::bind( &VisionReconfigure::QueueThread,this ) );
00043
00044
00045
00046
00047 this->pub_projector_ = this->nh_.advertise<std_msgs::Int32>("/projector_wg6802418_controller/projector", 1,true);
00048 this->pub_header_ = this->nh_.advertise<std_msgs::Header>("/projector_controller/rising_edge_timestamps", 1,true);
00049 dynamic_reconfigure::Server<gazebo_plugins::CameraSynchronizerConfig>::CallbackType f = boost::bind(&VisionReconfigure::ReconfigureCallback, this, _1, _2);
00050 this->srv_.setCallback(f);
00051
00052
00053
00054 gazebo_plugins::CameraSynchronizerConfig config;
00055 this->nh_.getParam("/camera_synchronizer_node/projector_mode",config.projector_mode);
00056 this->nh_.getParam("/camera_synchronizer_node/forearm_l_trig_mode",config.forearm_l_trig_mode);
00057 this->nh_.getParam("/camera_synchronizer_node/forearm_r_trig_mode",config.forearm_r_trig_mode);
00058 this->nh_.getParam("/camera_synchronizer_node/narrow_stereo_trig_mode",config.narrow_stereo_trig_mode);
00059 this->nh_.getParam("/camera_synchronizer_node/wide_stereo_trig_mode",config.wide_stereo_trig_mode);
00060 this->ReconfigureCallback(config,0);
00061
00062 }
00063
00064 VisionReconfigure::~VisionReconfigure()
00065 {
00066 this->nh_.shutdown();
00067 this->callback_queue_thread_.join();
00068 }
00069
00070 void VisionReconfigure::ReconfigureCallback(gazebo_plugins::CameraSynchronizerConfig &config, uint32_t level)
00071 {
00072
00073
00074 if (config.projector_mode == gazebo_plugins::CameraSynchronizer_ProjectorOff)
00075 {
00076 this->projector_msg_.data = 0;
00077 }
00078 else if (config.projector_mode == gazebo_plugins::CameraSynchronizer_ProjectorAuto)
00079 {
00080
00081 if (config.wide_stereo_trig_mode == gazebo_plugins::CameraSynchronizer_WithProjector ||
00082 config.narrow_stereo_trig_mode == gazebo_plugins::CameraSynchronizer_WithProjector ||
00083 config.forearm_r_trig_mode == gazebo_plugins::CameraSynchronizer_WithProjector ||
00084 config.forearm_l_trig_mode == gazebo_plugins::CameraSynchronizer_WithProjector)
00085 {
00086 this->projector_msg_.data = 1;
00087 }
00088 else if (config.wide_stereo_trig_mode == gazebo_plugins::CameraSynchronizer_AlternateProjector ||
00089 config.narrow_stereo_trig_mode == gazebo_plugins::CameraSynchronizer_AlternateProjector ||
00090 config.forearm_r_trig_mode == gazebo_plugins::CameraSynchronizer_AlternateProjector ||
00091 config.forearm_l_trig_mode == gazebo_plugins::CameraSynchronizer_AlternateProjector)
00092 {
00093 ROS_WARN("Alternate Projector Mode not supported in simulation, setting projector to on for now");
00094 this->projector_msg_.data = 1;
00095 }
00096 else
00097 {
00098 ROS_DEBUG("Projector only supported for modes: WithProjector and AlternateProjector");
00099 this->projector_msg_.data = 0;
00100 }
00101 }
00102 else if (config.projector_mode == gazebo_plugins::CameraSynchronizer_ProjectorOn)
00103 {
00104 this->projector_msg_.data = 1;
00105 }
00106 else
00107 {
00108 ROS_ERROR("projector_mode is not in any recognized state [%d]",config.projector_mode);
00109 }
00110
00111 this->pub_projector_.publish(projector_msg_);
00112 }
00113
00114 void VisionReconfigure::QueueThread()
00115 {
00116
00117 static const double timeout = 0.01;
00118 while (this->nh_.ok())
00119 {
00120 this->queue_.callAvailable(ros::WallDuration(timeout));
00121 }
00122 }
00123
00124 void VisionReconfigure::spinOnce()
00125 {
00126 if (projector_msg_.data == 1)
00127 {
00128 std_msgs::Header rh;
00129 rh.stamp = ros::Time::now();
00130 rh.frame_id = "projector_wg6802418_frame";
00131 this->pub_header_.publish(rh);
00132 }
00133 }
00134
00135 void VisionReconfigure::spin(double spin_frequency)
00136 {
00137 ros::Rate loop_rate(spin_frequency);
00138 while(this->nh_.ok())
00139 {
00140 ros::spinOnce();
00141 this->spinOnce();
00142 loop_rate.sleep();
00143 }
00144 }
00145