forked from srv/avt_vimba_camera
-
Notifications
You must be signed in to change notification settings - Fork 43
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
* Copy useful pieces from Wilhelm-Marais' branch * Add Action1 in addition to Action0 * Working trigger example, sends on all interfaces for simplicity * Add timer or subscriber-based trigger * Fix some code formatting * Revert sigint handler * Check return value of vimba startup
- Loading branch information
1 parent
5c8e96d
commit 2800e24
Showing
8 changed files
with
261 additions
and
4 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,53 @@ | ||
#ifndef AVT_VIMBA_CAMERA_TRIGGER_H | ||
#define AVT_VIMBA_CAMERA_TRIGGER_H | ||
|
||
#include "VimbaCPP/Include/VimbaCPP.h" | ||
|
||
#include <arpa/inet.h> | ||
|
||
#include <ros/ros.h> | ||
|
||
#include <std_msgs/Bool.h> | ||
|
||
namespace trigger | ||
{ | ||
|
||
class Trigger | ||
{ | ||
public: | ||
Trigger(); | ||
~Trigger(); | ||
|
||
void Init(); | ||
|
||
private: | ||
void LoadParams(); | ||
void InitializeAddress(); | ||
bool PrepareActionCommand(); | ||
bool SetIntFeatureValue(const std::string& name, int64_t value); | ||
|
||
void TimerCb(const ros::TimerEvent& event); | ||
void TriggerCb(const std_msgs::Bool::ConstPtr& msg); | ||
void SendActionCommand(); | ||
|
||
AVT::VmbAPI::VimbaSystem& vimba_system_; | ||
AVT::VmbAPI::InterfacePtr interface_ptr_; | ||
|
||
ros::NodeHandle pnh_; | ||
ros::NodeHandle nh_; | ||
|
||
ros::Timer trigger_timer_; | ||
ros::Subscriber trigger_sub_; | ||
|
||
// Params | ||
struct in_addr destination_ip_; | ||
std::string trigger_src_; | ||
float timer_period_; | ||
int action_device_key_; | ||
int action_group_key_; | ||
int action_group_mask_; | ||
}; | ||
|
||
} // namespace trigger | ||
|
||
#endif // AVT_VIMBA_CAMERA_TRIGGER_H |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,17 @@ | ||
<launch> | ||
<arg name="destination_ip" default="192.168.255.255" doc="The ip address of the camera/s to be triggered" /> | ||
<arg name="trigger_src" default="timer" doc="When to send action commands. Use 'timer' or 'subscriber'" /> | ||
<arg name="timer_period" default="0.1" doc="Period of timer for sending action commands (s)" /> | ||
<arg name="action_device_key" default="1" doc="The device key for the sent action" /> | ||
<arg name="action_group_key" default="1" doc="The group key for the sent actions" /> | ||
<arg name="action_group_mask" default="1" doc="The group mask for the sent actions" /> | ||
|
||
<node name="trigger_node" pkg="avt_vimba_camera" type="trigger_node" output="screen"> | ||
<param name="destination_ip" value="$(arg destination_ip)" /> | ||
<param name="trigger_src" value="$(arg trigger_src)" /> | ||
<param name="timer_period" value="$(arg timer_period)" /> | ||
<param name="action_device_key" value="$(arg action_device_key)" /> | ||
<param name="action_group_key" value="$(arg action_group_key)" /> | ||
<param name="action_group_mask" value="$(arg action_group_mask)" /> | ||
</node> | ||
</launch> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,12 @@ | ||
#include "avt_vimba_camera/trigger.h" | ||
|
||
int main(int argc, char* argv[]) | ||
{ | ||
ros::init(argc, argv, "trigger_node"); | ||
|
||
trigger::Trigger trigger; | ||
trigger.Init(); | ||
|
||
ros::spin(); | ||
return 0; | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,137 @@ | ||
#include "avt_vimba_camera/trigger.h" | ||
|
||
namespace trigger | ||
{ | ||
|
||
Trigger::Trigger() : vimba_system_(AVT::VmbAPI::VimbaSystem::GetInstance()), pnh_("~") | ||
{} | ||
|
||
Trigger::~Trigger() | ||
{ | ||
vimba_system_.Shutdown(); | ||
} | ||
|
||
void Trigger::Init() | ||
{ | ||
VmbErrorType return_value = vimba_system_.Startup(); | ||
|
||
if (return_value != VmbErrorSuccess) | ||
{ | ||
ROS_ERROR_STREAM("Failed to start Vimba system, vimba error code: " << return_value); | ||
ros::shutdown(); | ||
} | ||
|
||
LoadParams(); | ||
InitializeAddress(); | ||
|
||
if (trigger_src_ == "timer") | ||
{ | ||
trigger_timer_ = nh_.createTimer(ros::Duration(timer_period_), &Trigger::TimerCb, this); | ||
} | ||
else if (trigger_src_ == "subscriber") | ||
{ | ||
trigger_sub_ = nh_.subscribe("trigger_input", 10, &Trigger::TriggerCb, this); | ||
} | ||
else | ||
{ | ||
ROS_ERROR("Unknown trigger_src %s", trigger_src_.c_str()); | ||
ros::shutdown(); | ||
} | ||
} | ||
|
||
void Trigger::LoadParams() | ||
{ | ||
std::string destination_ip; | ||
pnh_.param<std::string>("destination_ip", destination_ip, "192.168.3.40"); | ||
pnh_.param<std::string>("trigger_src", trigger_src_, "timer"); | ||
pnh_.param<float>("timer_period", timer_period_, 0.1); | ||
pnh_.param<int>("action_device_key", action_device_key_, 1); | ||
pnh_.param<int>("action_group_key", action_group_key_, 1); | ||
pnh_.param<int>("action_group_mask", action_group_mask_, 1); | ||
|
||
if(inet_aton(destination_ip.c_str(), &destination_ip_) == 0) | ||
{ | ||
ROS_ERROR("Unable to parse desination_ip: %s", destination_ip.c_str()); | ||
ros::shutdown(); | ||
} | ||
} | ||
|
||
void Trigger::InitializeAddress() | ||
{ | ||
VmbErrorType return_value = VmbErrorSuccess; | ||
|
||
if (!SetIntFeatureValue("GevActionDestinationIPAddress", destination_ip_.s_addr)) | ||
{ | ||
ROS_ERROR("Could not set destination address"); | ||
} | ||
|
||
ROS_INFO("Destination address set"); | ||
} | ||
|
||
bool Trigger::PrepareActionCommand() | ||
{ | ||
return (SetIntFeatureValue("ActionDeviceKey", 1) && | ||
SetIntFeatureValue("ActionGroupKey", 1) && | ||
SetIntFeatureValue("ActionGroupMask", 1)); | ||
} | ||
|
||
// Sets an integer feature value on the vimba system | ||
bool Trigger::SetIntFeatureValue(const std::string& name, int64_t value) | ||
{ | ||
VmbErrorType return_value = VmbErrorSuccess; | ||
|
||
AVT::VmbAPI::FeaturePtr feature_ptr; | ||
return_value = vimba_system_.GetFeatureByName(name.c_str(), feature_ptr); | ||
|
||
if (return_value != VmbErrorSuccess) | ||
{ | ||
ROS_ERROR_STREAM("Failed to get feature, vimba error code: " << return_value); | ||
return false; | ||
} | ||
else | ||
{ | ||
return_value = feature_ptr->SetValue((VmbInt64_t)value); | ||
} | ||
|
||
return (return_value == VmbErrorSuccess); | ||
} | ||
|
||
void Trigger::TimerCb(const ros::TimerEvent& event) | ||
{ | ||
SendActionCommand(); | ||
} | ||
|
||
void Trigger::TriggerCb(const std_msgs::Bool::ConstPtr& msg) | ||
{ | ||
SendActionCommand(); | ||
} | ||
|
||
void Trigger::SendActionCommand() | ||
{ | ||
if (!PrepareActionCommand()) | ||
{ | ||
ROS_ERROR_THROTTLE(1.0, "Failed to prepare action command"); | ||
return; | ||
} | ||
|
||
VmbErrorType return_value = VmbErrorSuccess; | ||
|
||
AVT::VmbAPI::FeaturePtr lFeature; | ||
return_value = vimba_system_.GetFeatureByName("ActionCommand", lFeature ); | ||
|
||
if(return_value == VmbErrorSuccess) | ||
{ | ||
return_value = lFeature->RunCommand(); | ||
} | ||
|
||
if (return_value == VmbErrorSuccess) | ||
{ | ||
ROS_DEBUG("Action command sent"); | ||
} | ||
else | ||
{ | ||
ROS_ERROR_THROTTLE(1.0, "Failed to send action command"); | ||
} | ||
} | ||
|
||
} // namespace trigger |