trigger.h
Go to the documentation of this file.
1 #ifndef AVT_VIMBA_CAMERA_TRIGGER_H
2 #define AVT_VIMBA_CAMERA_TRIGGER_H
3 
5 
6 #include <arpa/inet.h>
7 
8 #include <ros/ros.h>
9 
10 #include <std_msgs/Bool.h>
11 
12 namespace trigger
13 {
14 class Trigger
15 {
16 public:
17  Trigger();
18  ~Trigger();
19 
20  void Init();
21 
22 private:
23  void LoadParams();
24  void InitializeAddress();
25  bool PrepareActionCommand();
26  bool SetIntFeatureValue(const std::string& name, int64_t value);
27 
28  void TimerCb(const ros::TimerEvent& event);
29  void TriggerCb(const std_msgs::Bool::ConstPtr& msg);
30  void SendActionCommand();
31 
33  AVT::VmbAPI::InterfacePtr interface_ptr_;
34 
37 
40 
41  // Params
42  struct in_addr destination_ip_;
43  std::string trigger_src_;
48 };
49 
50 } // namespace trigger
51 
52 #endif // AVT_VIMBA_CAMERA_TRIGGER_H
msg
ros::NodeHandle pnh_
Definition: trigger.h:35
struct in_addr destination_ip_
Definition: trigger.h:42
void LoadParams()
Definition: trigger.cpp:42
float timer_period_
Definition: trigger.h:44
void InitializeAddress()
Definition: trigger.cpp:59
AVT::VmbAPI::VimbaSystem & vimba_system_
Definition: trigger.h:32
ros::NodeHandle nh_
Definition: trigger.h:36
int action_group_mask_
Definition: trigger.h:47
int action_device_key_
Definition: trigger.h:45
void TriggerCb(const std_msgs::Bool::ConstPtr &msg)
Definition: trigger.cpp:103
ros::Subscriber trigger_sub_
Definition: trigger.h:39
ros::Timer trigger_timer_
Definition: trigger.h:38
bool SetIntFeatureValue(const std::string &name, int64_t value)
Definition: trigger.cpp:78
std::string trigger_src_
Definition: trigger.h:43
void TimerCb(const ros::TimerEvent &event)
Definition: trigger.cpp:98
void SendActionCommand()
Definition: trigger.cpp:108
bool PrepareActionCommand()
Definition: trigger.cpp:71
int action_group_key_
Definition: trigger.h:46
AVT::VmbAPI::InterfacePtr interface_ptr_
Definition: trigger.h:33


avt_vimba_camera
Author(s): Allied Vision Technologies, Miquel Massot
autogenerated on Fri Jun 2 2023 02:21:10