Go to the documentation of this file.
42 #include <sensor_msgs/Image.h>
43 #include <sensor_msgs/CameraInfo.h>
45 #include <sensor_msgs/SetCameraInfo.h>
46 #include <driver_base/SensorLevels.h>
54 #include <linux/sysctl.h>
57 #include <wge100_camera/BoardConfig.h>
58 #include <boost/tokenizer.hpp>
59 #include <boost/format.hpp>
67 #include <wge100_camera/WGE100CameraConfig.h>
73 #define RMEM_MAX_RECOMMENDED 20000000
89 for (
int i = 0; i < m.
rows; ++i) {
90 for (
int j = 0; j < m.
cols; ++j) {
99 const sensor_msgs::CameraInfo& cam_info)
104 out <<
"# Camera intrinsics\n\n";
106 out <<
"[image]\n\n";
107 out <<
"width\n" << cam_info.width <<
"\n\n";
108 out <<
"height\n" << cam_info.height <<
"\n\n";
109 out <<
"[" << camera_name <<
"]\n\n";
111 out <<
"camera matrix\n" <<
SimpleMatrix(3, 3, &cam_info.K[0]);
112 out <<
"\ndistortion\n" <<
SimpleMatrix(1, 5, &cam_info.D[0]);
113 out <<
"\n\nrectification\n" <<
SimpleMatrix(3, 3, &cam_info.R[0]);
114 out <<
"\nprojection\n" <<
SimpleMatrix(3, 4, &cam_info.P[0]);
155 FrameTimeFilter(
double frame_rate = 1.,
double late_locked_threshold = 1e-3,
double early_locked_threshold = 3e-3,
int early_recovery_frames = 5,
int max_recovery_frames = 10,
double max_skew = 1.001,
double max_skipped_frames = 100)
173 double run(
double in_time,
int frame_number)
175 double out_time = in_time;
192 bool early_trigger =
false;
196 early_trigger =
true;
220 return early_trigger ? -out_time : out_time;
293 typedef wge100_camera::WGE100CameraConfig
Config;
371 int bintable[5] = { -1, 0, 1, -1, 2 };
387 setStatusMessage(
"Error setting AGC/AEC mode. Exposure and gain may be incorrect.");
457 if (
config_.horizontal_binning == 3)
459 config_.horizontal_binning = 2;
460 ROS_WARN(
"horizontal_binning = 3 is invalid. Setting to 2.");
463 if (
config_.vertical_binning == 3)
466 ROS_WARN(
"horizontal_binning = 3 is invalid. Setting to 2.");
475 ROS_WARN(
"Exposure (%f s) is greater than 99%% of frame period (%f s). Setting to 99%% of frame period.",
486 ROS_WARN(
"Maximum exposure (%f s) is greater than 99%% of frame period (%f s). Setting to 99%% of frame period.",
510 std::ifstream
f(
"/proc/sys/net/core/rmem_max");
532 ROS_WARN_NAMED(
"rmem_max",
"rmem_max is %i. Buffer overflows and packet loss may occur. Minimum recommended value is 20000000. Updates may not take effect until the driver is restarted. See http://www.ros.org/wiki/wge100_camera/Troubleshooting",
rmem_max_);
553 ROS_INFO(
"Configured camera. Complete URLs: serial://%u@%s#%s name://%s@%s#%s",
573 setStatusMessage(
"External triggering is selected, but no \"trig_timestamp_topic\" was specified.");
641 setStatusMessage(
"Unable to find alternate imager context, but enable_alternate is true.");
683 bool is_MT9V032 =
imager_->getModel() ==
"MT9V032";
686 boost::recursive_mutex::scoped_lock lock(
mutex_);
687 setStatusMessagef(
"Camera has %s serial number, but has %s imager. This is a serious problem with the hardware.",
688 is_027 ?
"027" :
"non-027",
imager_->getModel().c_str());
763 ROS_ERROR(
"image_thread_ did not die after two seconds. Pretending that it did. This is probably a bad sign.");
772 status.
summary(2,
"Could not set imager into test mode.");
773 status.
add(
"Writing imager test mode",
"Fail");
778 status.
add(
"Writing imager test mode",
"Pass");
784 status.
summary(2,
"Could not read imager mode back.");
785 status.
add(
"Reading imager test mode",
"Fail");
790 status.
add(
"Reading imager test mode",
"Pass");
793 if (inmode != mode) {
794 status.
summary(2,
"Imager test mode read back did not match.");
795 status.
addf(
"Comparing read back value",
"Fail (%04x != %04x)", inmode, mode);
800 status.
add(
"Comparing read back value",
"Pass");
811 return (boost::format(
"WGE100_%05u") %
camera_.
serial).str();
842 if (since_last_frame_ > 10)
844 stat.
summary(2,
"Next frame is way past due.");
848 stat.
summary(1,
"Next frame is past due.");
852 stat.
summaryf(1,
"Frames are streaming, but the receive buffer is small (rmem_max=%u). Please increase rmem_max to %u to avoid dropped frames. For details: http://www.ros.org/wiki/wge100_camera/Troubleshooting",
rmem_max_,
RMEM_MAX_RECOMMENDED);
857 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"There have been dropped packets.");
862 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Frames are streaming.");
872 stat.
addf(
"First packet offset",
"%d",
config_.first_packet_offset);
875 static const std::string not_opened =
"not_opened";
876 stat.
add(
"Camera Serial #", not_opened);
877 stat.
add(
"Camera Name", not_opened);
878 stat.
add(
"Camera Hardware", not_opened);
879 stat.
add(
"Camera MAC", not_opened);
880 stat.
add(
"Interface", not_opened);
881 stat.
add(
"Camera IP", not_opened);
882 stat.
add(
"Image encoding", not_opened);
896 stat.
add(
"Image horizontal binning",
config_.horizontal_binning);
897 stat.
add(
"Image vertical binning",
config_.vertical_binning);
898 stat.
add(
"Requested imager rate",
config_.imager_rate);
901 stat.
add(
"External trigger controller",
config_.trig_timestamp_topic);
902 stat.
add(
"Trigger mode",
config_.ext_trig ?
"external" :
"internal");
906 stat.
add(
"Imager model", imager->getModel());
907 stat.
addf(
"Imager version",
"0x%04x", imager->getVersion());
937 double exposeEndTime = firstPacketTime -
config_.first_packet_offset +
941 return exposeEndTime;
948 return firstPacketTime -
config_.first_packet_offset;
970 boost::recursive_mutex::scoped_lock(diagnostics_lock_);
975 if (frame_info == NULL)
977 boost::recursive_mutex::scoped_lock lock(
mutex_);
982 const char *
msg =
"More than one second elapsed without receiving any trigger. Is this normal?";
994 setStatusMessagef(
"No data have arrived for more than one second. Assuming that camera is no longer streaming.");
1007 double firstPacketTime = frame_info->
startTime.tv_sec + frame_info->
startTime.tv_usec / 1e6;
1023 double triggerTimeGuess = firstPacketTimeFiltered -
config_.first_packet_offset;
1046 if (frame_delta > 1)
1049 ROS_DEBUG_NAMED(
"dropped_frame",
"Some frames were never seen. The dropped packet count will be incorrect.");
1054 if (frame_info->
eofInfo == NULL) {
1099 return imager_->getModel() ==
"MT9V032";
1115 for (
int i = 0; i < words; i++)
1116 sum += htons(
data[i]);
1117 return htons(0xFFFF - sum);
1128 ROS_WARN(
"Error reading camera intrinsics from flash.\n");
1135 ROS_WARN_NAMED(
"no_intrinsics",
"Camera intrinsics have a bad checksum. They have probably never been set.");
1142 if (success && (cam_info.width != (
unsigned int)
config_.width || cam_info.height != (
unsigned int)
config_.height)) {
1143 ROS_ERROR(
"Image resolution from intrinsics file does not match current video setting, "
1144 "intrinsics expect %ix%i but running at %ix%i", cam_info.width, cam_info.height,
config_.width,
config_.height);
1148 ROS_ERROR(
"Could not parse camera intrinsics downloaded from camera.");
1157 std::stringstream inifile;
1165 ROS_INFO(
"Writing camera info:\n%s", calbuff);
1167 boost::recursive_mutex::scoped_lock lock_(
mutex_);
1174 ROS_ERROR(
"Error putting camera into OPENED state to write to flash.\n");
1177 ROS_ERROR(
"Error writing camera intrinsics to flash.\n");
1180 ROS_INFO(
"Camera_info successfully written to camera.");
1189 bool boardConfig(wge100_camera::BoardConfig::Request &
req, wge100_camera::BoardConfig::Response &rsp)
1193 ROS_ERROR(
"board_config sevice called while camera was not running. To avoid programming the wrong camera, board_config can only be called while viewing the camera stream.");
1199 if (
req.mac.size() != 6)
1201 ROS_ERROR(
"board_config service called with %zu bytes in MAC. Should be 6.",
req.mac.size());
1205 for (
int i = 0; i < 6; i++)
1206 mac[i] =
req.mac[i];
1207 ROS_INFO(
"board_config called s/n #%i, and MAC %02x:%02x:%02x:%02x:%02x:%02x.",
req.serial, mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]);
1212 ROS_INFO(
"board_config succeeded.");
1244 if (topic == alt_topic)
1286 ROS_DEBUG(
"WGE100CameraNode::reconfigureHook called at level %x", level);
1297 ROS_INFO(
"Loaded intrinsics from camera.");
1300 ROS_WARN_NAMED(
"no_intrinsics",
"Failed to load intrinsics from camera");
1306 if (
driver_.config_.ext_trig && !
driver_.config_.trig_timestamp_topic.empty())
1328 bool setCameraInfo(sensor_msgs::SetCameraInfo::Request &
req, sensor_msgs::SetCameraInfo::Response &rsp)
1330 sensor_msgs::CameraInfo &cam_info =
req.camera_info;
1334 ROS_ERROR(
"set_camera_info service called while camera was not running. To avoid programming the wrong camera, set_camera_info can only be called while viewing the camera stream.");
1335 rsp.status_message =
"Camera not running. Camera must be running to avoid setting the intrinsics of the wrong camera.";
1336 rsp.success =
false;
1340 if ((cam_info.width != (
unsigned int)
driver_.config_.width || cam_info.height != (
unsigned int)
driver_.config_.height)) {
1341 ROS_ERROR(
"Image resolution of camera_info passed to set_camera_info service does not match current video setting, "
1342 "camera_info contains %ix%i but camera running at %ix%i", cam_info.width, cam_info.height,
driver_.config_.width,
driver_.config_.height);
1343 rsp.status_message = (boost::format(
"Camera_info resolution %ix%i does not match camera resolution %ix%i.")%cam_info.width%cam_info.height%
driver_.config_.width%
driver_.config_.height).str();
1344 rsp.success =
false;
1347 rsp.success =
driver_.saveIntrinsics(cam_info);
1349 rsp.status_message =
"Error writing camera_info to flash.";
1360 ROS_DEBUG(
"Adding wge100 camera video mode tests.");
1373 for (
int i = 0; i < 10; i++)
1410 ROS_WARN(
"Unexpected imager_id, autodetecting test pattern for this camera.");
1415 for (
size_t y = 0; y <
height; y++)
1416 for (
size_t x = 0; x <
width; x++,
data++)
1436 ROS_WARN(
"Pattern mismatch, retrying...");
1455 #define NUM_TEST_PATTERNS 3
1459 col[0] = (x + 2 * y + 25) / 4;
1460 if ((x + 1) / 2 + y < 500)
1461 col[1] = 14 + x / 4;
1464 col[2] = (x + 2 * y + 43) / 4;
1470 if (col[mode] == actual_col)
1473 msg = (boost::format(
"Unexpected value %u instead of %u at (x=%u, y=%u)")%(int)actual_col%(
int)col[mode]%x%y).str();
1478 if (col[i] == actual_col)
1484 msg = (boost::format(
"Unexpected value in first pixel %u, expected: %u, %u or %u")%(int)actual_col%(
int)col[0]%(int)col[1]%(
int)col[2]).str();
1499 ROS_ERROR(
"Tried to call videoModeTest with out of range mode %u.", mode);
1509 new_config.x_offset = 0;
1510 new_config.y_offset = 0;
1512 new_config.ext_trig = 0;
1513 new_config.register_set = wge100_camera::WGE100Camera_PrimaryRegisterSet;
1514 new_config.test_pattern =
true;
1515 driver_.config_update(new_config);
1520 status.name = (boost::format(
"Pattern Test: %ix%i at %.1f fps.")%new_config.width%new_config.height%new_config.imager_rate).str();
1523 int oldcount =
driver_.lost_image_thread_count_;
1524 for (
int i = 0; i < 50 && !callback.
got_frame_; i++)
1532 ROS_ERROR(
"Got no frame during pattern test.");
1533 status.
summary(2,
"Got no frame during pattern test.");
1535 if (oldcount <
driver_.lost_image_thread_count_)
1537 ROS_ERROR(
"Lost the image_thread. This should never happen.");
1538 status.
summary(2,
"Lost the image_thread. This should never happen.");
1541 driver_.useFrame_ = oldUseFrame;
1542 driver_.config_update(old_config);
1544 ROS_INFO(
"Exiting test %s with status %i: %s", status.name.c_str(), status.level, status.message.c_str());
1550 return driver_base::main<WGE100CameraNode>(argc, argv,
"wge100_camera");
#define FLASH_CALIBRATION_PAGENO
#define TRIG_STATE_ALTERNATE
void addTask(DiagnosticTask *t)
void setStatusMessagef(const char *format,...)
self_test::TestRunner self_test_
MT9VImagerPtr alternate_imager_
int wge100VidReceiveAuto(IpCamList *camera, size_t height, size_t width, FrameHandler frameHandler, void *userData)
virtual bool setMirror(bool mirrorx, bool mirrory)=0
static int frameHandler(wge100FrameInfo *frameInfo, void *userData)
void streamingTest(diagnostic_updater::DiagnosticStatusWrapper &status)
SimpleMatrix(int rows, int cols, const double *data)
uint16_t i2c[I2C_REGS_PER_FRAME]
Storage for I2C values read during the frame.
UseFrameFunction useFrame_
int wge100ReliableSensorRead(const IpCamList *camInfo, uint8_t reg, uint16_t *data, int *retries)
int trigger_matcher_drop_count_
VideoModeTestFrameHandler(diagnostic_updater::DiagnosticStatusWrapper &status, int imager_id)
int early_recovery_frames_
virtual void addOpenedTests()
int wge100ImagerSetRes(const IpCamList *camInfo, uint16_t horizontal, uint16_t vertical)
void add(const std::string &key, const bool &b)
image_transport::CameraPublisher cam_pub_
boost::recursive_mutex mutex_
uint16_t intrinsicsChecksum(uint16_t *data, int words)
int wge100TriggerControl(const IpCamList *camInfo, uint32_t triggerType)
double last_camera_ok_time_
int wge100Configure(IpCamList *camInfo, const char *ipAddress, unsigned wait_us)
static MT9VImagerPtr getInstance(IpCamList &cam)
sensor_msgs::Image image_
double getTriggeredFrameTime(double firstPacketTime)
FrameTimeFilter(double frame_rate=1., double late_locked_threshold=1e-3, double early_locked_threshold=3e-3, int early_recovery_frames=5, int max_recovery_frames=10, double max_skew=1.001, double max_skipped_frames=100)
boost::shared_ptr< boost::thread > image_thread_
int black_level_step_size
virtual bool setCompanding(bool activated)=0
image_transport::CameraPublisher cam_pub_alt_
double getExternallyTriggeredFrameTime(double firstPacketTime)
diagnostic_updater::CompositeDiagnosticTask driver_status_diagnostic_
#define TRIG_STATE_RISING
#define IMAGER_LINENO_OVF
Flags this video packet as being an Overflow packet.
unsigned int last_frame_number_
diagnostic_updater::DiagnosticStatusWrapper & status_
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
virtual bool setMode(int x, int y, int binx, int biny, double rate, int xoffset, int yoffset)=0
void setStatusMessage(const std::string &msg, bool ok=false, bool recovery_complete=false)
ros::NodeHandle camera_node_handle_alt_
int setTestMode(uint16_t mode, diagnostic_updater::DiagnosticStatusWrapper &status)
int wge100ReliableFlashRead(const IpCamList *camInfo, uint32_t address, uint8_t *pageDataOut, int *retries)
timestamp_tools::TriggerMatcher trigger_matcher_
diagnostic_updater::Updater diagnostic_
const struct MT9VMode MT9VModes[MT9V_NUM_MODES]
void cameraStatus(diagnostic_updater::DiagnosticStatusWrapper &stat)
std::string resolveName(const std::string &name, bool remap=true) const
virtual bool setBlackLevel(bool manual_override, int calibration_value, int step_size, int filter_length)=0
void add(const std::string &name, TaskFunction f)
bool loadIntrinsics(sensor_msgs::CameraInfo &cam_info)
#define ROS_INFO_COND(cond,...)
void summary(const diagnostic_msgs::DiagnosticStatus &src)
int black_level_filter_length
#define ROS_DEBUG_NAMED(name,...)
int wge100ConfigureBoard(const IpCamList *camInfo, uint32_t serial, MACAddress *mac)
#define TRIG_STATE_INTERNAL
virtual bool setMaxExposure(double exposure)=0
std::string image_encoding_
int wge100ReliableFlashWrite(const IpCamList *camInfo, uint32_t address, const uint8_t *pageDataIn, int *retries)
const std::string BAYER_BGGR8
static const state_t OPENED
std::ostream & operator<<(std::ostream &out, const SimpleMatrix &m)
virtual std::string getID()=0
ros::ServiceServer config_bord_service_
ros::NodeHandle camera_node_handle_
FrameTimeFilter frame_time_filter_
ros::NodeHandle private_node_handle_
ros::Subscriber trigger_sub_
ros::NodeHandle node_handle_
void videoModeTest(int mode, diagnostic_updater::DiagnosticStatusWrapper &status)
SlowTriggerFilter no_timestamp_warning_filter_
unsigned int last_partial_frame_number_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
boost::function< void(DiagnosticStatusWrapper &)> TaskFunction
diagnostic_updater::TopicDiagnostic cam_pub_diag_
bool setCameraInfo(sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &rsp)
virtual bool setBrightness(int brightness)=0
double early_locked_threshold_
int frameHandler(wge100FrameInfo *frame_info)
SlowTriggerFilter(int before_warn, int before_clear)
void setHardwareID(const std::string &hwid)
double driver_start_time_
int setImagerSettings(MT9VImager &imager, ImagerSettings &cfg)
static const state_t CLOSED
static const state_t RUNNING
virtual bool setGain(int gain)=0
std::string check_expected(int x, int y, uint8_t actual_col, bool final, int &mode)
double run(double in_time, int frame_number)
ros::ServiceClient trig_service_
virtual void addStoppedTests()
int main(int argc, char **argv)
int massive_frame_losses_
bool boardConfig(wge100_camera::BoardConfig::Request &req, wge100_camera::BoardConfig::Response &rsp)
bool saveIntrinsics(const sensor_msgs::CameraInfo &cam_info)
#define RMEM_MAX_RECOMMENDED
ros::ServiceServer set_camera_info_service_
double getFreeRunningFrameTime(double firstPacketTime)
int wge100EthGetLocalMac(const char *ifName, struct sockaddr *macAddr)
int lost_image_thread_count_
int run(size_t width, size_t height, uint8_t *data, ros::Time stamp, bool alternate)
wge100_camera::WGE100CameraConfig Config
#define TRIG_STATE_EXTERNAL
#define ROS_WARN_NAMED(name,...)
void addf(const std::string &key, const char *format,...)
boost::function< int(size_t, size_t, uint8_t *, ros::Time, bool)> UseFrameFunction
char hwinfo[WGE100_CAMINFO_LEN]
virtual void reconfigureHook(int level)
bool dropped_packet_event_
void config_update(const Config &new_cfg, uint32_t level=0)
int wge100SensorSelect(const IpCamList *camInfo, uint8_t index, uint32_t reg)
virtual void run(DiagnosticStatusWrapper &stat)
bool parseCalibration(const std::string &buffer, const std::string &format, std::string &camera_name, sensor_msgs::CameraInfo &cam_info)
virtual void addRunningTests()
int publishImage(size_t width, size_t height, uint8_t *frameData, ros::Time t, bool alternate)
#define NUM_TEST_PATTERNS
#define IMAGER_LINENO_ERR
Flags this video packet as being a General Error packet.
virtual bool setAgcAec(bool agc_on, bool aec_on)=0
bool writeCalibrationIni(std::ostream &out, const std::string &camera_name, const sensor_msgs::CameraInfo &cam_info)
int wge100FindByUrl(const char *url, IpCamList *camera, unsigned wait_us, const char **errmsg)
void setPostOpenHook(hookFunction f)
void summaryf(unsigned char lvl, const char *format,...)
int wge100ReliableSensorWrite(const IpCamList *camInfo, uint8_t reg, uint16_t data, int *retries)
WGE100CameraNode(ros::NodeHandle &nh)
virtual bool setExposure(double exposure)=0
sensor_msgs::CameraInfo camera_info_
double late_locked_threshold_
DriverNode(ros::NodeHandle &nh)
int wge100IpGetLocalAddr(const char *ifName, struct in_addr *addr)
diagnostic_updater::FunctionDiagnosticTask wge100_diagnostic_task_
char cam_name[CAMERA_NAME_LEN]
virtual void addDiagnostics()
wge100_camera
Author(s): Blaise Gassend, Patrick Mihelich, Eric MacIntosh, David Palchak
autogenerated on Tue Mar 7 2023 03:59:26