fix(ros): fix camera info bug
This commit is contained in:
parent
84145cd35c
commit
7bc74f4d1b
|
@ -1290,7 +1290,8 @@ class ROSWrapperNodelet : public nodelet::Nodelet {
|
||||||
}
|
}
|
||||||
for (int i = 0; i < p.rows; i++) {
|
for (int i = 0; i < p.rows; i++) {
|
||||||
for (int j = 0; j < p.cols; j++) {
|
for (int j = 0; j < p.cols; j++) {
|
||||||
camera_info->P.at(i * p.cols + j) = p.at<double>(i, j);
|
int scale = (i == 2 && j == 2)?1:1000;
|
||||||
|
camera_info->P.at(i * p.cols + j) = p.at<double>(i, j) / scale;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue
Block a user