42 p2os_(p2os), max_zoom_(MAX_ZOOM_OPTIC), pan_(0), tilt_(0), zoom_(0),
43 is_on_(false), error_code_(CAM_ERROR_NONE),
44 bidirectional_com_(bidirectional_com)
61 for (
int i = 1; i < num_inits; i++) {
74 ROS_DEBUG(
"Waiting for camera to power on.");
81 ROS_DEBUG(
"Waiting for camera mode to set");
88 ROS_DEBUG(
"Waiting for camera to initialize");
95 for(
int i = 0; i < 3; i++)
97 ROS_DEBUG(
"Waiting for camera to set default tilt");
105 ROS_DEBUG(
"Waiting for camera to set initial pan and tilt");
112 ROS_DEBUG(
"Waiting for camera to set initial zoom");
124 ROS_ERROR(
"Error initiliazing PTZ at stage %i", i);
128 ROS_ERROR(
"Error: CAM_ERROR_BUSY");
131 ROS_ERROR(
"Error: CAM_ERROR_PARAM");
134 ROS_ERROR(
"Error: CAM_ERROR_MODE");
137 ROS_ERROR(
"Error: Unknown error response from camera.");
144 ROS_DEBUG(
"Passed stage %i of PTZ initialization.", i);
147 ROS_DEBUG(
"Finished initialization of the PTZ.");
159 ROS_INFO(
"PTZ camera has been shutdown");
164 p2os_msgs::PTZState to_send;
165 bool change_pan_tilt =
false;
166 bool change_zoom =
false;
168 to_send.tilt =
tilt_;
169 to_send.zoom =
zoom_;
176 to_send.pan = cmd->pan +
pan_;
177 change_pan_tilt =
true;
181 to_send.tilt = cmd->tilt +
tilt_;
182 change_pan_tilt =
true;
186 to_send.zoom = cmd->zoom +
zoom_;
194 to_send.pan = cmd->pan;
195 change_pan_tilt =
true;
199 to_send.tilt = cmd->tilt;
200 change_pan_tilt =
true;
204 to_send.zoom = cmd->zoom;
230 unsigned char request[4];
237 request_pkt.
Build(request,4);
242 ROS_ERROR(
"Command message is too large to send");
253 memcpy(&mybuf[3], str, len);
254 ptz_packet.
Build(mybuf, len+3);
266 unsigned char request[4];
273 request_pkt.
Build(request,4);
278 ROS_ERROR(
"Request message is too large to send.");
289 memcpy(&mybuf[3], str, len);
290 ptz_packet.
Build(mybuf, len+3);
318 ROS_ERROR(
"circbuf error!");
323 byte = (
unsigned char)t;
325 if (byte == (
unsigned char)
RESPONSE)
335 ROS_ERROR(
"Length is 0 on received packet.");
346 if (reply[len - 1] != (
unsigned char)
FOOTER)
348 ROS_ERROR(
"canonvcc4::receiveCommandAnswer: Discarding bad packet.");
357 reply[len] = (
unsigned char)t;
365 ROS_ERROR(
"Answer does not equal command response bytes");
370 if (reply[0] != (
unsigned char)
RESPONSE || reply[5] != (
unsigned char)
FOOTER)
372 ROS_ERROR(
"Header or Footer is wrong on received packet");
386 ROS_ERROR(
"Error: CAM_ERROR_BUSY");
389 ROS_ERROR(
"Error: CAM_ERROR_PARAM");
392 ROS_ERROR(
"Error: CAM_ERROR_MODE");
395 ROS_ERROR(
"Error: Unknown error response from camera.");
429 ROS_ERROR(
"circbuf error!\n");
433 byte = (
unsigned char)t;
435 if (byte == (
unsigned char)
RESPONSE)
444 ROS_ERROR(
"Received Request Answer has length 0");
454 if (reply[len - 1] != (
unsigned char)
FOOTER)
456 ROS_ERROR(
"Last Byte was not the footer!");
465 reply[len] = (
unsigned char)t;
472 ROS_ERROR(
"Response Length was incorrect at %i.", len);
476 if (reply[0] != (
unsigned char)
RESPONSE ||
477 reply[len - 1] != (
unsigned char)
FOOTER)
479 ROS_ERROR(
"Header or Footer is wrong on received packet");
488 memcpy(data, reply, len);
494 ROS_ERROR(
"Error: CAM_ERROR_BUSY");
497 ROS_ERROR(
"Error: CAM_ERROR_PARAM");
500 ROS_ERROR(
"Error: CAM_ERROR_MODE");
503 ROS_ERROR(
"Error: Unknown error response from camera.");
512 unsigned char request[4];
514 bool secondSent =
false;
525 request_pkt.
Build(request,4);
532 ROS_ERROR(
"Waiting for packet timed out.");
535 if (
cb_.
size() == s1 && !secondSent)
540 int newsize = s2 - s1;
541 ROS_ERROR(
"Requesting Second Packet of size %i.", newsize);
542 request[2] = newsize;
543 request_pkt.
Build(request,4);
550 ROS_ERROR(
"Got reply from AUX1 But don't have a full packet.");
647 unsigned char buf[4];
676 for (i = 0; i < 4; i++)
682 byte = byte -
'A' + 10;
688 for (i = 0; i < 4; i++)
689 u_zoom += buf[i] * (
unsigned int) pow(16.0, (
double)(3 - i));
700 unsigned char buf[4];
727 for (i = 0; i < 4; i++)
733 byte = byte -
'A' + 10;
739 for (i = 0; i < 4; i++)
740 u_zoom += buf[i] * (
unsigned int) pow(16.0, (
double)(3 - i));
748 unsigned char buf[5];
765 sprintf((
char *)buf,
"%4X", zoom);
797 unsigned char buf[5];
798 int maxtilt, mintilt;
807 mintilt = (int)(floor(
MIN_TILT/.1125) + 0x8000);
808 sprintf((
char*)buf,
"%X", mintilt);
813 maxtilt = (int)(floor(
MAX_TILT/.1125) + 0x8000);
814 sprintf((
char*)buf,
"%X", maxtilt);
816 command[10] = buf[0];
817 command[11] = buf[1];
818 command[12] = buf[2];
819 command[13] = buf[3];
843 unsigned char buf[4];
867 if ( reply_len != 14 ) {
868 ROS_ERROR(
"Reply Len = %i; should equal 14", reply_len);
873 for (i = 0; i < 4; i++)
879 byte = byte -
'A' + 10;
884 u_val = buf[0] * 0x1000 + buf[1] * 0x100 + buf[2] * 0x10 + buf[3];
887 val = (int)(((
int)u_val - (
int)0x8000) * 0.1125);
893 for (i = 0; i < 4; i++)
899 byte = byte -
'A' + 10;
902 u_val = buf[0] * 0x1000 + buf[1] * 0x100 + buf[2] * 0x10 + buf[3];
903 val =(int)(((
int)u_val - (int)0x8000) * 0.1125);
912 int convpan, convtilt;
913 unsigned char buf[5];
916 ppan = pan; ttilt = tilt;
938 convpan = (int)floor(ppan/.1125) + 0x8000;
939 convtilt = (int)floor(ttilt/.1125) + 0x8000;
949 snprintf((
char *)buf,
sizeof(buf),
"%X", convpan);
956 snprintf((
char *)buf,
sizeof(buf),
"%X", convtilt);
958 command[10] = buf[1];
959 command[11] = buf[2];
960 command[12] = buf[3];
961 command[13] = (
unsigned char)
FOOTER;
985 start(0), end(0), mysize(size), gotPack(false)
987 this->
buf =
new unsigned char[
size];
994 printf(
"0x%x ",
buf[i]);
1020 return !(this->
start == this->
end);
Illegal parameters to function call.
static const int MAX_COMMAND_LENGTH
int SendReceive(P2OSPacket *pkt, bool publish_data=true)
Requests max zoom position.
P2OSPtz(P2OSNode *p2os, bool bidirectional_com=false)
Request pan/tilt position.
int setDefaultTiltRange()
Pan/tilt min/max range assignment.
int sendCommand(unsigned char *str, int len)
Puts camera in Control mode.
int getAbsPanTilt(int *pan, int *tilt)
static const int PACKET_TIMEOUT
int receiveCommandAnswer(int asize)
Not in host control mode.
void putOnBuf(unsigned char c)
Packet header for response.
int sendAbsZoom(int zoom)
int Build(unsigned char *data, unsigned char datasize)
static const int TILT_THRESH
void getPtzPacket(int s1, int s2=0)
static const int SLEEP_TIME_USEC
void callback(const p2os_msgs::PTZStateConstPtr &msg)
static const int COMMAND_RESPONSE_BYTES
int sendAbsPanTilt(int pan, int tilt)
static const int PAN_THRESH
int receiveRequestAnswer(unsigned char *data, int s1, int s2)
static const int MAX_REQUEST_LENGTH
static const int ZOOM_THRESH
int getAbsZoom(int *zoom)
int sendRequest(unsigned char *str, int len, unsigned char *reply)
Camera busy, will not execute the command.
int getMaxZoom(int *max_zoom)
p2os_msgs::PTZState current_state_