Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Improve rosout logging #50

Merged
merged 6 commits into from
Nov 26, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion cfg/AvtVimbaCamera.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -189,7 +189,7 @@ gen.add("offset_y", int_t, SensorLevels.RECONFIGURE_RUNNING, "Y
# PIXEL FORMAT
gen.add("pixel_format", str_t, SensorLevels.RECONFIGURE_CLOSE, "Format of the image data.", "Mono8", edit_method=pixelformat_enum)
# BANDWIDTH
gen.add("stream_bytes_per_second",int_t, SensorLevels.RECONFIGURE_RUNNING, "Limits the data rate of the camera.", 45000000, 1, 115000000)
gen.add("stream_bytes_per_second",int_t, SensorLevels.RECONFIGURE_RUNNING, "Limits the data rate of the camera.", 124000000, 1, 125000000)
# PTP
gen.add("ptp_mode", str_t, SensorLevels.RECONFIGURE_RUNNING, "Controls the PTP behavior of the clock port.", "Off", edit_method=ptp_mode_enum)
# GPIO
Expand Down
94 changes: 67 additions & 27 deletions include/avt_vimba_camera/avt_vimba_api.h
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ class AvtVimbaApi {

/** Translates Vimba error codes to readable error messages
*
* @param error Vimba error tyme
* @param error Vimba error type
* @return readable string error
*
**/
Expand Down Expand Up @@ -100,6 +100,33 @@ class AvtVimbaApi {
return "Unsupported error code passed.";
}

std::string interfaceToString(VmbInterfaceType interfaceType) {
switch (interfaceType) {
case VmbInterfaceFirewire: return "FireWire";
break;
case VmbInterfaceEthernet: return "GigE";
break;
case VmbInterfaceUsb: return "USB";
break;
default: return "Unknown";
}
}

std::string accessModeToString(VmbAccessModeType modeType) {
if (modeType & VmbAccessModeFull)
return "Read and write access";
else if (modeType & VmbAccessModeRead)
return "Only read access";
else if (modeType & VmbAccessModeConfig)
return "Device configuration access";
else if (modeType & VmbAccessModeLite)
return "Device read/write access without feature access (only addresses)";
else if (modeType & VmbAccessModeNone)
return "No access";
else
return "Undefined access";
}

bool frameToImage(const FramePtr vimba_frame_ptr, sensor_msgs::Image& image) {
VmbPixelFormatType pixel_format;
VmbUint32_t width, height, nSize;
Expand Down Expand Up @@ -171,55 +198,68 @@ class AvtVimbaApi {
VimbaSystem& vs;

void listAvailableCameras(void) {
std::string name;
ROS_INFO("Searching for cameras ...");
CameraPtrVector cameras;
if (VmbErrorSuccess == vs.Startup()) {
if (VmbErrorSuccess == vs.GetCameras(cameras)) {
for (CameraPtrVector::iterator iter = cameras.begin();

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

how about for (const auto& camera : cameras)?

cameras.end() != iter;
++iter) {
if (VmbErrorSuccess == (*iter)->GetName(name)) {
ROS_DEBUG_STREAM("[" << ros::this_node::getName() << "]: Found camera: ");
for (const auto& camera : cameras) {
std::string strID;
std::string strName;
std::string strModelname;
std::string strSerialNumber;
std::string strInterfaceID;
VmbInterfaceType interfaceType;
VmbAccessModeType accessType;

VmbErrorType err = camera->GetID( strID );
if ( VmbErrorSuccess != err )
{
ROS_ERROR_STREAM("[Could not get camera ID. Error code: " << err << "]");
}
std::string strID; // The ID of the cam
std::string strName; // The name of the cam
std::string strModelname; // The model name of the cam
std::string strSerialNumber; // The serial number of the cam
std::string strInterfaceID; // The ID of the interface the cam is connected to
VmbErrorType err = (*iter)->GetID( strID );

err = camera->GetName( strName );
if ( VmbErrorSuccess != err )
{
ROS_ERROR_STREAM("[Could not get camera ID. Error code: " << err << "]");
ROS_ERROR_STREAM("[Could not get camera name. Error code: " << err << "]");
}
err = (*iter)->GetName( strName );

err = camera->GetModel( strModelname );
if ( VmbErrorSuccess != err )
{
ROS_ERROR_STREAM("[Could not get camera mode name. Error code: " << err << "]");
}

err = camera->GetSerialNumber( strSerialNumber );
if ( VmbErrorSuccess != err )
{
ROS_ERROR_STREAM("[Could not get camera name. Error code: " << err << "]");
ROS_ERROR_STREAM("[Could not get camera serial number. Error code: " << err << "]");
}

err = (*iter)->GetModel( strModelname );
err = camera->GetInterfaceID( strInterfaceID );
if ( VmbErrorSuccess != err )
{
ROS_ERROR_STREAM("[Could not get camera mode name. Error code: " << err << "]");
ROS_ERROR_STREAM("[Could not get interface ID. Error code: " << err << "]");
}

err = (*iter)->GetSerialNumber( strSerialNumber );
err = camera->GetInterfaceType( interfaceType );
if ( VmbErrorSuccess != err )
{
ROS_ERROR_STREAM("[Could not get camera serial number. Error code: " << err << "]");
ROS_ERROR_STREAM("[Could not get interface type. Error code: " << err << "]");
}

err = (*iter)->GetInterfaceID( strInterfaceID );
err = camera->GetPermittedAccess( accessType );
if ( VmbErrorSuccess != err )
{
ROS_ERROR_STREAM("[Could not get interface ID. Error code: " << err << "]");
ROS_ERROR_STREAM("[Could not get access type. Error code: " << err << "]");
}
ROS_INFO_STREAM("\t/// Camera Name: " << strName);
ROS_INFO_STREAM("\t/// Model Name: " << strModelname);
ROS_INFO_STREAM("\t/// Camera ID: " << strID);
ROS_INFO_STREAM("\t/// Serial Number: " << strSerialNumber);
ROS_INFO_STREAM("\t/// @ Interface ID: " << strInterfaceID);

ROS_INFO_STREAM("Found camera named " << strName << ":");
ROS_INFO_STREAM(" - Model Name : " << strModelname);
ROS_INFO_STREAM(" - Camera ID : " << strID);
ROS_INFO_STREAM(" - Serial Number : " << strSerialNumber);
ROS_INFO_STREAM(" - Interface ID : " << strInterfaceID);
ROS_INFO_STREAM(" - Interface type : " << interfaceToString(interfaceType));
ROS_INFO_STREAM(" - Access type : " << accessModeToString(accessType));
}
} else {
ROS_WARN("Could not get cameras from Vimba System");
Expand Down
12 changes: 4 additions & 8 deletions include/avt_vimba_camera/avt_vimba_camera.h
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ class AvtVimbaCamera {
public:
AvtVimbaCamera();
AvtVimbaCamera(const std::string& name);
void start(const std::string& ip_str, const std::string& guid_str, const std::string& frame_id, bool debug_prints = true);
void start(const std::string& ip_str, const std::string& guid_str, const std::string& frame_id, bool print_all_features = false);
void stop();
double getTimestamp(void);
double getTimestampRealTime(VmbUint64_t timestamp_ticks);
Expand Down Expand Up @@ -128,7 +128,6 @@ class AvtVimbaCamera {
bool opened_;
bool streaming_;
bool on_init_;
bool show_debug_prints_;
std::string name_;

diagnostic_updater::Updater updater_;
Expand All @@ -142,7 +141,7 @@ class AvtVimbaCamera {
std::string trigger_source_;
int trigger_source_int_;

CameraPtr openCamera(std::string id_str);
CameraPtr openCamera(const std::string& id_str, bool print_all_features);

frameCallbackFunc userFrameCallback;
void frameCallback(const FramePtr vimba_frame_ptr);
Expand All @@ -151,17 +150,14 @@ class AvtVimbaCamera {
}

template<typename T>
bool setFeatureValue(const std::string& feature_str, const T& val);
template<typename T>
bool setGetFeatureValue(const std::string& feature_str, const T& val_in, T& val_out);
VmbErrorType setFeatureValue(const std::string& feature_str, const T& val);
template<typename Vimba_Type, typename Std_Type>
void configureFeature(const std::string& feature_str, const Vimba_Type& val_in, Std_Type& val_out);
void configureFeature(const std::string& feature_str, const std::string& val_in, std::string& val_out);
template<typename T>
bool getFeatureValue(const std::string& feature_str, T& val);
bool getFeatureValue(const std::string& feature_str, std::string& val);
bool runCommand(const std::string& command_str);
std::string interfaceToString(VmbInterfaceType interfaceType);
std::string accessModeToString(VmbAccessModeType modeType);
int getTriggerModeInt(std::string mode_str);
void printAllCameraFeatures(const CameraPtr& camera);

Expand Down
2 changes: 1 addition & 1 deletion include/avt_vimba_camera/mono_camera.h
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ class MonoCamera {
std::string guid_;
std::string camera_info_url_;
std::string frame_id_;
bool show_debug_prints_;
bool print_all_features_;
bool use_measurement_time_;
int32_t ptp_offset_;

Expand Down
4 changes: 2 additions & 2 deletions launch/mono_camera.launch
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
<arg name="ptp_offset" default="-37" doc="Offset to add to the timestamp from the camera (s).
Useful for converting from TAI to UTC time. Only applies if use_measurement_time is true"/>
<arg name="camera_info_url" default="file://$(find avt_vimba_camera)/calibrations/calibration_example.yaml"/>
<arg name="show_debug_prints" default="true" doc="Show debug output on console"/>
<arg name="print_all_features" default="false" doc="Show all camera features on the console during startup"/>
<arg name="image_proc" default="false" doc="Launch image_proc with driver"/>

<!-- Camera parameters, these parameters are used to configure the AVT camera upon startup -->
Expand Down Expand Up @@ -86,7 +86,7 @@
<param name="use_measurement_time" value="$(arg use_measurement_time)"/>
<param name="ptp_offset" value="$(arg ptp_offset)"/>
<param name="camera_info_url" value="$(arg camera_info_url)"/>
<param name="show_debug_prints" value="$(arg show_debug_prints)"/>=
<param name="print_all_features" value="$(arg print_all_features)"/>

<param name="acquisition_mode" value="$(arg acquisition_mode)"/>
<param name="acquisition_rate" value="$(arg acquisition_rate)"/>
Expand Down
Loading