trigger.cpp
Go to the documentation of this file.
2 
3 namespace trigger
4 {
5 Trigger::Trigger() : vimba_system_(AVT::VmbAPI::VimbaSystem::GetInstance()), pnh_("~")
6 {
7 }
8 
10 {
12 }
13 
15 {
16  VmbErrorType return_value = vimba_system_.Startup();
17 
18  if (return_value != VmbErrorSuccess)
19  {
20  ROS_ERROR_STREAM("Failed to start Vimba system, vimba error code: " << return_value);
21  ros::shutdown();
22  }
23 
24  LoadParams();
26 
27  if (trigger_src_ == "timer")
28  {
30  }
31  else if (trigger_src_ == "subscriber")
32  {
33  trigger_sub_ = nh_.subscribe("trigger_input", 10, &Trigger::TriggerCb, this);
34  }
35  else
36  {
37  ROS_ERROR("Unknown trigger_src %s", trigger_src_.c_str());
38  ros::shutdown();
39  }
40 }
41 
43 {
44  std::string destination_ip;
45  pnh_.param<std::string>("destination_ip", destination_ip, "192.168.3.40");
46  pnh_.param<std::string>("trigger_src", trigger_src_, "timer");
47  pnh_.param<float>("timer_period", timer_period_, 0.1);
48  pnh_.param<int>("action_device_key", action_device_key_, 1);
49  pnh_.param<int>("action_group_key", action_group_key_, 1);
50  pnh_.param<int>("action_group_mask", action_group_mask_, 1);
51 
52  if (inet_aton(destination_ip.c_str(), &destination_ip_) == 0)
53  {
54  ROS_ERROR("Unable to parse desination_ip: %s", destination_ip.c_str());
55  ros::shutdown();
56  }
57 }
58 
60 {
61  VmbErrorType return_value = VmbErrorSuccess;
62 
63  if (!SetIntFeatureValue("GevActionDestinationIPAddress", destination_ip_.s_addr))
64  {
65  ROS_ERROR("Could not set destination address");
66  }
67 
68  ROS_INFO("Destination address set");
69 }
70 
72 {
73  return (SetIntFeatureValue("ActionDeviceKey", action_device_key_) && SetIntFeatureValue("ActionGroupKey", action_group_key_) &&
74  SetIntFeatureValue("ActionGroupMask", action_group_mask_));
75 }
76 
77 // Sets an integer feature value on the vimba system
78 bool Trigger::SetIntFeatureValue(const std::string& name, int64_t value)
79 {
80  VmbErrorType return_value = VmbErrorSuccess;
81 
82  AVT::VmbAPI::FeaturePtr feature_ptr;
83  return_value = vimba_system_.GetFeatureByName(name.c_str(), feature_ptr);
84 
85  if (return_value != VmbErrorSuccess)
86  {
87  ROS_ERROR_STREAM("Failed to get feature, vimba error code: " << return_value);
88  return false;
89  }
90  else
91  {
92  return_value = feature_ptr->SetValue((VmbInt64_t)value);
93  }
94 
95  return (return_value == VmbErrorSuccess);
96 }
97 
99 {
101 }
102 
103 void Trigger::TriggerCb(const std_msgs::Bool::ConstPtr& msg)
104 {
106 }
107 
109 {
110  if (!PrepareActionCommand())
111  {
112  ROS_ERROR_THROTTLE(1.0, "Failed to prepare action command");
113  return;
114  }
115 
116  VmbErrorType return_value = VmbErrorSuccess;
117 
118  AVT::VmbAPI::FeaturePtr lFeature;
119  return_value = vimba_system_.GetFeatureByName("ActionCommand", lFeature);
120 
121  if (return_value == VmbErrorSuccess)
122  {
123  return_value = lFeature->RunCommand();
124  }
125 
126  if (return_value == VmbErrorSuccess)
127  {
128  ROS_DEBUG("Action command sent");
129  }
130  else
131  {
132  ROS_ERROR_THROTTLE(1.0, "Failed to send action command");
133  }
134 }
135 
136 } // namespace trigger
IMEXPORT VmbErrorType GetFeatureByName(const char *pName, FeaturePtr &pFeature)
ros::NodeHandle pnh_
Definition: trigger.h:35
long long VmbInt64_t
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
IMEXPORT VmbErrorType Startup()
Definition: VimbaSystem.cpp:93
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
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
VmbErrorType
void TriggerCb(const std_msgs::Bool::ConstPtr &msg)
Definition: trigger.cpp:103
bool param(const std::string &param_name, T &param_val, const T &default_val) const
#define ROS_INFO(...)
#define ROS_ERROR_THROTTLE(period,...)
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
ROSCPP_DECL void shutdown()
IMEXPORT VmbErrorType Shutdown()
#define ROS_ERROR_STREAM(args)
bool PrepareActionCommand()
Definition: trigger.cpp:71
int action_group_key_
Definition: trigger.h:46
#define ROS_ERROR(...)
#define ROS_DEBUG(...)


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