Go to the documentation of this file.
24 #ifndef CAMERA_ARAVIS_CAMERA_ARAVIS_NODELET
25 #define CAMERA_ARAVIS_CAMERA_ARAVIS_NODELET
42 #include <unordered_map>
48 #include <nodelet/NodeletUnload.h>
51 #include <sensor_msgs/Image.h>
52 #include <std_msgs/Int64.h>
55 #include <boost/algorithm/string/trim.hpp>
57 #include <yaml-cpp/yaml.h>
59 #include <dynamic_reconfigure/server.h>
60 #include <dynamic_reconfigure/SensorLevels.h>
64 #include <camera_aravis/CameraAravisConfig.h>
65 #include <camera_aravis/CameraAutoInfo.h>
66 #include <camera_aravis/CameraDiagnostics.h>
67 #include <camera_aravis/ExtendedCameraInfo.h>
69 #include <camera_aravis/get_integer_feature_value.h>
70 #include <camera_aravis/set_integer_feature_value.h>
71 #include <camera_aravis/get_float_feature_value.h>
72 #include <camera_aravis/set_float_feature_value.h>
73 #include <camera_aravis/get_string_feature_value.h>
74 #include <camera_aravis/set_string_feature_value.h>
75 #include <camera_aravis/get_boolean_feature_value.h>
76 #include <camera_aravis/set_boolean_feature_value.h>
77 #include <camera_aravis/one_shot_white_balance.h>
85 typedef CameraAravisConfig
Config;
95 std::string
guid_ =
"";
152 bool getIntegerFeatureCallback(camera_aravis::get_integer_feature_value::Request& request, camera_aravis::get_integer_feature_value::Response& response);
155 bool getFloatFeatureCallback(camera_aravis::get_float_feature_value::Request& request, camera_aravis::get_float_feature_value::Response& response);
158 bool getStringFeatureCallback(camera_aravis::get_string_feature_value::Request& request, camera_aravis::get_string_feature_value::Response& response);
161 bool getBooleanFeatureCallback(camera_aravis::get_boolean_feature_value::Request& request, camera_aravis::get_boolean_feature_value::Response& response);
164 bool setIntegerFeatureCallback(camera_aravis::set_integer_feature_value::Request& request, camera_aravis::set_integer_feature_value::Response& response);
167 bool setFloatFeatureCallback(camera_aravis::set_float_feature_value::Request& request, camera_aravis::set_float_feature_value::Response& response);
170 bool setStringFeatureCallback(camera_aravis::set_string_feature_value::Request& request, camera_aravis::set_string_feature_value::Response& response);
173 bool setBooleanFeatureCallback(camera_aravis::set_boolean_feature_value::Request& request, camera_aravis::set_boolean_feature_value::Response& response);
176 bool oneShotWhiteBalanceCallback(camera_aravis::one_shot_white_balance::Request& request, camera_aravis::one_shot_white_balance::Response& response);
187 static void parseStringArgs(std::string in_arg_string, std::vector<std::string> &out_args);
204 std::vector<image_transport::CameraPublisher>
cam_pubs_;
209 std::unique_ptr<tf2_ros::StaticTransformBroadcaster>
p_stb_;
210 std::unique_ptr<tf2_ros::TransformBroadcaster>
p_tb_;
std::string ptp_status_feature_
std::atomic_bool tf_thread_active_
ros::Subscriber auto_sub_
bool setStringFeatureCallback(camera_aravis::set_string_feature_value::Request &request, camera_aravis::set_string_feature_value::Response &response)
std::thread tf_dyn_thread_
void rosConnectCallback()
double diagnostic_publish_rate_
static void newBufferReady(ArvStream *p_stream, CameraAravisNodelet *p_can, std::string frame_id, size_t stream_id)
bool oneShotWhiteBalanceCallback(camera_aravis::one_shot_white_balance::Request &request, camera_aravis::one_shot_white_balance::Response &response)
std::thread diagnostic_thread_
void fillExtendedCameraInfoMessage(ExtendedCameraInfo &msg)
void setExtendedCameraInfo(std::string channel_name, size_t stream_id)
std::unique_ptr< tf2_ros::TransformBroadcaster > p_tb_
ros::ServiceServer get_integer_service_
geometry_msgs::TransformStamped tf_optical_
CameraAravisNodelet * can
ros::ServiceServer set_integer_service_
virtual ~CameraAravisNodelet()
std::vector< ros::Publisher > extended_camera_info_pubs_
std::thread software_trigger_thread_
std::vector< ConversionFunction > convert_formats
void syncAutoParameters()
CameraAravisConfig Config
ros::ServiceServer one_shot_white_balance_service_
ros::ServiceServer get_boolean_service_
std::vector< ArvStream * > p_streams_
bool getIntegerFeatureCallback(camera_aravis::get_integer_feature_value::Request &request, camera_aravis::get_integer_feature_value::Response &response)
ros::Publisher diagnostic_pub_
std::string ptp_enable_feature_
bool getStringFeatureCallback(camera_aravis::get_string_feature_value::Request &request, camera_aravis::get_string_feature_value::Response &response)
bool getBooleanFeatureCallback(camera_aravis::get_boolean_feature_value::Request &request, camera_aravis::get_boolean_feature_value::Response &response)
void publishTfLoop(double rate)
std::string diagnostic_yaml_url_
ros::Timer shutdown_trigger_
std::vector< Sensor * > sensors_
std::vector< sensor_msgs::CameraInfoPtr > camera_infos_
ros::ServiceServer get_string_service_
std::thread spawn_stream_thread_
std::vector< std::unique_ptr< ros::NodeHandle > > p_camera_info_node_handles_
bool setIntegerFeatureCallback(camera_aravis::set_integer_feature_value::Request &request, camera_aravis::set_integer_feature_value::Response &response)
std::unique_ptr< dynamic_reconfigure::Server< Config > > reconfigure_server_
void tuneGvStream(ArvGvStream *p_stream)
void onShutdownTriggered(const ros::TimerEvent &)
ros::ServiceServer set_boolean_service_
boost::recursive_mutex extended_camera_info_mutex_
void writeCameraFeaturesFromRosparam()
YAML::Node diagnostic_features_
static void newBufferReadyCallback(ArvStream *p_stream, gpointer can_instance)
std::vector< std::string > stream_names_
std::vector< std::unique_ptr< camera_info_manager::CameraInfoManager > > p_camera_info_managers_
ros::ServiceServer set_float_service_
ros::ServiceServer set_string_service_
std::atomic< bool > spawning_
std::vector< image_transport::CameraPublisher > cam_pubs_
struct camera_aravis::CameraAravisNodelet::@0 roi_
bool setBooleanFeatureCallback(camera_aravis::set_boolean_feature_value::Request &request, camera_aravis::set_boolean_feature_value::Response &response)
CameraAutoInfo auto_params_
void rosReconfigureCallback(Config &config, uint32_t level)
bool pub_ext_camera_info_
static void parseStringArgs(std::string in_arg_string, std::vector< std::string > &out_args)
virtual void onInit() override
boost::recursive_mutex reconfigure_mutex_
std::atomic_bool diagnostic_thread_active_
bool setFloatFeatureCallback(camera_aravis::set_float_feature_value::Request &request, camera_aravis::set_float_feature_value::Response &response)
void setAutoMaster(bool value)
void softwareTriggerLoop()
static void controlLostCallback(ArvDevice *p_gv_device, gpointer can_instance)
ros::ServiceServer get_float_service_
std::atomic_bool software_trigger_active_
std::string ptp_set_cmd_feature_
bool getFloatFeatureCallback(camera_aravis::get_float_feature_value::Request &request, camera_aravis::get_float_feature_value::Response &response)
std::unique_ptr< tf2_ros::StaticTransformBroadcaster > p_stb_
std::vector< CameraBufferPool::Ptr > p_buffer_pools_
std::unordered_map< std::string, const bool > implemented_features_
void setAutoSlave(bool value)
void readAndPublishCameraDiagnostics(double rate) const
void cameraAutoInfoCallback(const CameraAutoInfoConstPtr &msg_ptr)
camera_aravis
Author(s): Boitumelo Ruf, Fraunhofer IOSB
, Dominik Kleiser, Fraunhofer IOSB , Dominik A. Klein, Fraunhofer FKIE , Steve Safarik, Straw Lab , Andrew Straw, Straw Lab , Floris van Breugel, van Breugel Lab
autogenerated on Wed Sep 25 2024 02:23:21