
Classes | |
| struct | ImagerSettings |
Public Types | |
| typedef wge100_camera::WGE100CameraConfig | Config |
Public Types inherited from driver_base::Driver | |
| typedef char | state_t |
Public Attributes | |
| Config | config_ |
Public Attributes inherited from driver_base::Driver | |
| boost::recursive_mutex | mutex_ |
Private Types | |
| typedef boost::function< int(size_t, size_t, uint8_t *, ros::Time, bool)> | UseFrameFunction |
Private Member Functions | |
| bool | boardConfig (wge100_camera::BoardConfig::Request &req, wge100_camera::BoardConfig::Response &rsp) |
| void | cameraStatus (diagnostic_updater::DiagnosticStatusWrapper &stat) |
| int | frameHandler (wge100FrameInfo *frame_info) |
| double | getExternallyTriggeredFrameTime (double firstPacketTime) |
| double | getFreeRunningFrameTime (double firstPacketTime) |
| double | getTriggeredFrameTime (double firstPacketTime) |
| void | imageThread () |
| uint16_t | intrinsicsChecksum (uint16_t *data, int words) |
| bool | isColor () |
| bool | loadIntrinsics (sensor_msgs::CameraInfo &cam_info) |
| bool | saveIntrinsics (const sensor_msgs::CameraInfo &cam_info) |
| int | setImagerSettings (MT9VImager &imager, ImagerSettings &cfg) |
Static Private Member Functions | |
| static int | frameHandler (wge100FrameInfo *frameInfo, void *userData) |
Private Attributes | |
| MT9VImagerPtr | alternate_imager_ |
| IpCamList | camera_ |
| double | desired_freq_ |
| double | driver_start_time_ |
| bool | dropped_packet_event_ |
| int | dropped_packets_ |
| bool | enable_alternate_ |
| bool | enable_primary_ |
| bool | first_frame_ |
| FrameTimeFilter | frame_time_filter_ |
| std::string | hwinfo_ |
| std::string | image_encoding_ |
| boost::shared_ptr< boost::thread > | image_thread_ |
| MT9VImagerPtr | imager_ |
| double | last_camera_ok_time_ |
| unsigned int | last_frame_number_ |
| double | last_image_time_ |
| unsigned int | last_partial_frame_number_ |
| in_addr | localIp_ |
| sockaddr | localMac_ |
| int | lost_image_thread_count_ |
| int | massive_frame_losses_ |
| int | missed_eof_count_ |
| int | missed_line_count_ |
| bool | next_is_alternate_ |
| SlowTriggerFilter | no_timestamp_warning_filter_ |
| int | rmem_max_ |
| ros::ServiceClient | trig_service_ |
| timestamp_tools::TriggerMatcher | trigger_matcher_ |
| int | trigger_matcher_drop_count_ |
| UseFrameFunction | useFrame_ |
Friends | |
| class | WGE100CameraNode |
Additional Inherited Members | |
Static Public Member Functions inherited from driver_base::Driver | |
| static const std::string & | getStateName (state_t s) |
Static Public Attributes inherited from driver_base::Driver | |
| static const state_t | CLOSED |
| static const state_t | OPENED |
| static const state_t | RUNNING |
Protected Types inherited from driver_base::Driver | |
| typedef boost::function< void() > | hookFunction |
Protected Attributes inherited from driver_base::Driver | |
| hookFunction | postOpenHook |
| state_t | state_ |
Definition at line 288 of file wge100_camera_node.cpp.
| typedef wge100_camera::WGE100CameraConfig WGE100CameraDriver::Config |
Definition at line 293 of file wge100_camera_node.cpp.
|
private |
Definition at line 341 of file wge100_camera_node.cpp.
|
inline |
Definition at line 433 of file wge100_camera_node.cpp.
|
inline |
Definition at line 500 of file wge100_camera_node.cpp.
|
inlineprivate |
Definition at line 1189 of file wge100_camera_node.cpp.
|
inlineprivate |
Definition at line 839 of file wge100_camera_node.cpp.
|
inline |
Definition at line 453 of file wge100_camera_node.cpp.
|
inlinevirtual |
Implements driver_base::Driver.
Definition at line 704 of file wge100_camera_node.cpp.
|
inlinevirtual |
Implements driver_base::Driver.
Definition at line 516 of file wge100_camera_node.cpp.
|
inlinevirtual |
Implements driver_base::Driver.
Definition at line 712 of file wge100_camera_node.cpp.
|
inlinevirtual |
Implements driver_base::Driver.
Definition at line 750 of file wge100_camera_node.cpp.
|
inlineprivate |
Do we want to support rates less than 1 Hz?
Definition at line 968 of file wge100_camera_node.cpp.
|
inlinestaticprivate |
Definition at line 1106 of file wge100_camera_node.cpp.
|
inline |
Definition at line 506 of file wge100_camera_node.cpp.
|
inlineprivate |
Definition at line 931 of file wge100_camera_node.cpp.
|
inlineprivate |
Definition at line 944 of file wge100_camera_node.cpp.
|
inlinevirtual |
Implements driver_base::Driver.
Definition at line 806 of file wge100_camera_node.cpp.
|
inlineprivate |
Definition at line 911 of file wge100_camera_node.cpp.
|
inlineprivate |
Definition at line 815 of file wge100_camera_node.cpp.
|
inlineprivate |
Definition at line 1112 of file wge100_camera_node.cpp.
|
inlineprivate |
Definition at line 1097 of file wge100_camera_node.cpp.
|
inlineprivate |
Definition at line 1120 of file wge100_camera_node.cpp.
|
inlineprivate |
Definition at line 1153 of file wge100_camera_node.cpp.
|
inlineprivate |
Definition at line 369 of file wge100_camera_node.cpp.
|
inline |
Definition at line 769 of file wge100_camera_node.cpp.
|
friend |
Definition at line 290 of file wge100_camera_node.cpp.
|
private |
Definition at line 329 of file wge100_camera_node.cpp.
|
private |
Definition at line 327 of file wge100_camera_node.cpp.
| Config WGE100CameraDriver::config_ |
Definition at line 294 of file wge100_camera_node.cpp.
|
private |
Definition at line 301 of file wge100_camera_node.cpp.
|
private |
Definition at line 312 of file wge100_camera_node.cpp.
|
private |
Definition at line 308 of file wge100_camera_node.cpp.
|
private |
Definition at line 306 of file wge100_camera_node.cpp.
|
private |
Definition at line 334 of file wge100_camera_node.cpp.
|
private |
Definition at line 335 of file wge100_camera_node.cpp.
|
private |
Definition at line 333 of file wge100_camera_node.cpp.
|
private |
Definition at line 318 of file wge100_camera_node.cpp.
|
private |
Definition at line 326 of file wge100_camera_node.cpp.
|
private |
Definition at line 331 of file wge100_camera_node.cpp.
|
private |
Definition at line 338 of file wge100_camera_node.cpp.
|
private |
Definition at line 328 of file wge100_camera_node.cpp.
|
private |
Definition at line 330 of file wge100_camera_node.cpp.
|
private |
Definition at line 313 of file wge100_camera_node.cpp.
|
private |
Definition at line 311 of file wge100_camera_node.cpp.
|
private |
Definition at line 314 of file wge100_camera_node.cpp.
|
private |
Definition at line 323 of file wge100_camera_node.cpp.
|
private |
Definition at line 322 of file wge100_camera_node.cpp.
|
private |
Definition at line 315 of file wge100_camera_node.cpp.
|
private |
Definition at line 307 of file wge100_camera_node.cpp.
|
private |
Definition at line 305 of file wge100_camera_node.cpp.
|
private |
Definition at line 309 of file wge100_camera_node.cpp.
|
private |
Definition at line 332 of file wge100_camera_node.cpp.
|
private |
Definition at line 966 of file wge100_camera_node.cpp.
|
private |
Definition at line 304 of file wge100_camera_node.cpp.
|
private |
Definition at line 298 of file wge100_camera_node.cpp.
|
private |
Definition at line 319 of file wge100_camera_node.cpp.
|
private |
Definition at line 310 of file wge100_camera_node.cpp.
|
private |
Definition at line 342 of file wge100_camera_node.cpp.