#include <astra_driver.h>
Public Member Functions | |
AstraDriver (ros::NodeHandle &n, ros::NodeHandle &pnh) | |
~AstraDriver () | |
Private Types | |
typedef astra_camera::AstraConfig | Config |
typedef dynamic_reconfigure::Server< Config > | ReconfigureServer |
Private Member Functions | |
void | advertiseROSTopics () |
void | applyConfigToOpenNIDevice () |
void | configCb (Config &config, uint32_t level) |
sensor_msgs::CameraInfo | convertAstraCameraInfo (OBCameraParams p, ros::Time time) const |
void | depthConnectCb () |
void | genVideoModeTableMap () |
bool | getCameraInfoCb (astra_camera::GetCameraInfoRequest &req, astra_camera::GetCameraInfoResponse &res) |
sensor_msgs::CameraInfoPtr | getColorCameraInfo (int width, int height, ros::Time time) const |
sensor_msgs::CameraInfoPtr | getDefaultCameraInfo (int width, int height, double f) const |
sensor_msgs::CameraInfoPtr | getDepthCameraInfo (int width, int height, ros::Time time) const |
bool | getDeviceTypeCb (astra_camera::GetDeviceTypeRequest &req, astra_camera::GetDeviceTypeResponse &res) |
sensor_msgs::CameraInfoPtr | getIRCameraInfo (int width, int height, ros::Time time) const |
bool | getIRExposureCb (astra_camera::GetIRExposureRequest &req, astra_camera::GetIRExposureResponse &res) |
bool | getIRGainCb (astra_camera::GetIRGainRequest &req, astra_camera::GetIRGainResponse &res) |
sensor_msgs::CameraInfoPtr | getProjectorCameraInfo (int width, int height, ros::Time time) const |
bool | getSerialCb (astra_camera::GetSerialRequest &req, astra_camera::GetSerialResponse &res) |
void | imageConnectCb () |
void | initDevice () |
int | lookupVideoModeFromDynConfig (int mode_nr, AstraVideoMode &video_mode) |
void | newColorFrameCallback (sensor_msgs::ImagePtr image) |
void | newDepthFrameCallback (sensor_msgs::ImagePtr image) |
void | newIRFrameCallback (sensor_msgs::ImagePtr image) |
sensor_msgs::ImageConstPtr | rawToFloatingPointConversion (sensor_msgs::ImageConstPtr raw_image) |
void | readConfigFromParameterServer () |
bool | resetIRExposureCb (astra_camera::ResetIRExposureRequest &req, astra_camera::ResetIRExposureResponse &res) |
bool | resetIRGainCb (astra_camera::ResetIRGainRequest &req, astra_camera::ResetIRGainResponse &res) |
std::string | resolveDeviceURI (const std::string &device_id) |
void | setColorVideoMode (const AstraVideoMode &color_video_mode) |
void | setDepthVideoMode (const AstraVideoMode &depth_video_mode) |
bool | setIRExposureCb (astra_camera::SetIRExposureRequest &req, astra_camera::SetIRExposureResponse &res) |
bool | setIRFloodCb (astra_camera::SetIRFloodRequest &req, astra_camera::SetIRFloodResponse &res) |
bool | setIRGainCb (astra_camera::SetIRGainRequest &req, astra_camera::SetIRGainResponse &res) |
void | setIRVideoMode (const AstraVideoMode &ir_video_mode) |
bool | setLaserCb (astra_camera::SetLaserRequest &req, astra_camera::SetLaserResponse &res) |
bool | setLDPCb (astra_camera::SetLDPRequest &req, astra_camera::SetLDPResponse &res) |
bool | switchIRCameraCb (astra_camera::SwitchIRCameraRequest &req, astra_camera::SwitchIRCameraResponse &res) |
Definition at line 75 of file astra_driver.h.
|
private |
Definition at line 82 of file astra_driver.h.
|
private |
Definition at line 83 of file astra_driver.h.
astra_wrapper::AstraDriver::AstraDriver | ( | ros::NodeHandle & | n, |
ros::NodeHandle & | pnh | ||
) |
Definition at line 51 of file astra_driver.cpp.
astra_wrapper::AstraDriver::~AstraDriver | ( | ) |
Definition at line 157 of file astra_driver.cpp.
|
private |
Definition at line 161 of file astra_driver.cpp.
|
private |
Definition at line 467 of file astra_driver.cpp.
Definition at line 328 of file astra_driver.cpp.
|
private |
Definition at line 706 of file astra_driver.cpp.
|
private |
Definition at line 592 of file astra_driver.cpp.
|
private |
Definition at line 1146 of file astra_driver.cpp.
|
private |
Definition at line 305 of file astra_driver.cpp.
|
private |
Definition at line 783 of file astra_driver.cpp.
|
private |
Definition at line 748 of file astra_driver.cpp.
|
private |
Definition at line 918 of file astra_driver.cpp.
|
private |
Definition at line 251 of file astra_driver.cpp.
|
private |
Definition at line 849 of file astra_driver.cpp.
|
private |
Definition at line 269 of file astra_driver.cpp.
|
private |
Definition at line 257 of file astra_driver.cpp.
|
private |
Definition at line 934 of file astra_driver.cpp.
|
private |
Definition at line 245 of file astra_driver.cpp.
|
private |
Definition at line 528 of file astra_driver.cpp.
|
private |
Definition at line 1106 of file astra_driver.cpp.
|
private |
Definition at line 1294 of file astra_driver.cpp.
|
private |
Definition at line 632 of file astra_driver.cpp.
|
private |
Definition at line 648 of file astra_driver.cpp.
|
private |
Definition at line 616 of file astra_driver.cpp.
|
private |
Definition at line 1311 of file astra_driver.cpp.
|
private |
Definition at line 945 of file astra_driver.cpp.
|
private |
Definition at line 299 of file astra_driver.cpp.
|
private |
Definition at line 293 of file astra_driver.cpp.
|
private |
Definition at line 967 of file astra_driver.cpp.
|
private |
Definition at line 438 of file astra_driver.cpp.
|
private |
Definition at line 452 of file astra_driver.cpp.
|
private |
Definition at line 275 of file astra_driver.cpp.
|
private |
Definition at line 311 of file astra_driver.cpp.
|
private |
Definition at line 263 of file astra_driver.cpp.
|
private |
Definition at line 423 of file astra_driver.cpp.
|
private |
Definition at line 281 of file astra_driver.cpp.
|
private |
Definition at line 287 of file astra_driver.cpp.
|
private |
Definition at line 317 of file astra_driver.cpp.
|
private |
Definition at line 162 of file astra_driver.h.
|
private |
Definition at line 207 of file astra_driver.h.
|
private |
Definition at line 208 of file astra_driver.h.
|
private |
Definition at line 184 of file astra_driver.h.
|
private |
Definition at line 179 of file astra_driver.h.
|
private |
Camera info manager objects.
Definition at line 172 of file astra_driver.h.
|
private |
Definition at line 182 of file astra_driver.h.
|
private |
Definition at line 211 of file astra_driver.h.
|
private |
Definition at line 196 of file astra_driver.h.
|
private |
Definition at line 175 of file astra_driver.h.
|
private |
Definition at line 160 of file astra_driver.h.
|
private |
Definition at line 163 of file astra_driver.h.
|
private |
Definition at line 199 of file astra_driver.h.
|
private |
Definition at line 202 of file astra_driver.h.
|
private |
Definition at line 203 of file astra_driver.h.
|
private |
Definition at line 201 of file astra_driver.h.
|
private |
Definition at line 180 of file astra_driver.h.
|
private |
Definition at line 190 of file astra_driver.h.
|
private |
Definition at line 191 of file astra_driver.h.
|
private |
Definition at line 213 of file astra_driver.h.
|
private |
Definition at line 185 of file astra_driver.h.
|
private |
Definition at line 212 of file astra_driver.h.
|
private |
Definition at line 197 of file astra_driver.h.
|
private |
Definition at line 176 of file astra_driver.h.
|
private |
Definition at line 139 of file astra_driver.h.
|
private |
Definition at line 141 of file astra_driver.h.
|
private |
Definition at line 138 of file astra_driver.h.
|
private |
get_serial server
Definition at line 144 of file astra_driver.h.
|
private |
Definition at line 146 of file astra_driver.h.
|
private |
Definition at line 149 of file astra_driver.h.
|
private |
Definition at line 147 of file astra_driver.h.
|
private |
Definition at line 145 of file astra_driver.h.
|
private |
Definition at line 178 of file astra_driver.h.
|
private |
Definition at line 172 of file astra_driver.h.
|
private |
Definition at line 182 of file astra_driver.h.
|
private |
Definition at line 210 of file astra_driver.h.
|
private |
Definition at line 195 of file astra_driver.h.
|
private |
Definition at line 174 of file astra_driver.h.
|
private |
Definition at line 135 of file astra_driver.h.
|
private |
Definition at line 218 of file astra_driver.h.
|
private |
Definition at line 136 of file astra_driver.h.
|
private |
Definition at line 214 of file astra_driver.h.
|
private |
Definition at line 165 of file astra_driver.h.
|
private |
Definition at line 166 of file astra_driver.h.
|
private |
Definition at line 167 of file astra_driver.h.
|
private |
Definition at line 168 of file astra_driver.h.
|
private |
Definition at line 169 of file astra_driver.h.
|
private |
reconfigure server
Definition at line 159 of file astra_driver.h.
|
private |
Definition at line 155 of file astra_driver.h.
|
private |
Definition at line 154 of file astra_driver.h.
|
private |
Definition at line 205 of file astra_driver.h.
|
private |
Definition at line 150 of file astra_driver.h.
|
private |
Definition at line 151 of file astra_driver.h.
|
private |
Definition at line 148 of file astra_driver.h.
|
private |
Definition at line 152 of file astra_driver.h.
|
private |
Definition at line 153 of file astra_driver.h.
|
private |
Definition at line 156 of file astra_driver.h.
|
private |
Definition at line 216 of file astra_driver.h.
|
private |
Definition at line 219 of file astra_driver.h.
|
private |
Definition at line 187 of file astra_driver.h.
|
private |
Definition at line 192 of file astra_driver.h.
|
private |
Definition at line 193 of file astra_driver.h.