20 ROS_ERROR_STREAM(
"Failed to start Vimba system, vimba error code: " << return_value);
44 std::string destination_ip;
45 pnh_.
param<std::string>(
"destination_ip", destination_ip,
"192.168.3.40");
54 ROS_ERROR(
"Unable to parse desination_ip: %s", destination_ip.c_str());
65 ROS_ERROR(
"Could not set destination address");
82 AVT::VmbAPI::FeaturePtr feature_ptr;
87 ROS_ERROR_STREAM(
"Failed to get feature, vimba error code: " << return_value);
92 return_value = feature_ptr->SetValue((
VmbInt64_t)value);
118 AVT::VmbAPI::FeaturePtr lFeature;
123 return_value = lFeature->RunCommand();
IMEXPORT VmbErrorType GetFeatureByName(const char *pName, FeaturePtr &pFeature)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
IMEXPORT VmbErrorType Startup()
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_
AVT::VmbAPI::VimbaSystem & vimba_system_
void TriggerCb(const std_msgs::Bool::ConstPtr &msg)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
#define ROS_ERROR_THROTTLE(period,...)
ros::Subscriber trigger_sub_
ros::Timer trigger_timer_
bool SetIntFeatureValue(const std::string &name, int64_t value)
void TimerCb(const ros::TimerEvent &event)
ROSCPP_DECL void shutdown()
IMEXPORT VmbErrorType Shutdown()
#define ROS_ERROR_STREAM(args)
bool PrepareActionCommand()