Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix cam name var #105

Merged
merged 5 commits into from
Nov 16, 2023
Merged
Show file tree
Hide file tree
Changes from 4 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion analyst/tools/query_view_points.cc
Original file line number Diff line number Diff line change
Expand Up @@ -114,7 +114,7 @@ int main(int argc, char** argv) {
new geometry_msgs::Transform(msg_conversions::eigen_transform_to_ros_transform(transform_body_to_cam)));

camera::CameraParameters cam_params(&config, FLAGS_camera.c_str());
inspection::CameraView camera(cam_params, 2.0, 0.19, msg_pointer);
inspection::CameraView camera(FLAGS_camera.c_str(), cam_params, 2.0, 0.19, msg_pointer);


// Extract the input list from the command-line argument
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ class CameraView : public camera::CameraModel {
// f: far clip, maximum camera distance (m)
// n: near clip, minimum camera distance (m)
// cam_transform: transform from body->camera, useful for offline applications where tf is not available
CameraView(const camera::CameraParameters & params, const float f = 2.0, const float n = 0.19,
CameraView(const std::string, const camera::CameraParameters & params, const float f = 2.0, const float n = 0.19,
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
CameraView(const std::string, const camera::CameraParameters & params, const float f = 2.0, const float n = 0.19,
CameraView(const std::string& cam_name, const camera::CameraParameters & params, const float f = 2.0, const float n = 0.19,

(Usually better to pass std::string as ref to avoid unnecessary extra copy, also style consistency of including the argument name.)

const geometry_msgs::Transform::ConstPtr cam_transform = NULL);


Expand Down
7 changes: 3 additions & 4 deletions astrobee/behaviors/inspection/src/camera_projection.cc
Original file line number Diff line number Diff line change
Expand Up @@ -34,10 +34,9 @@ namespace inspection {
the camera frame and the other way around. It automatically reads the camera parameters
from the config files based on the camera name, such that no setup is necessary.
*/
CameraView::CameraView(const camera::CameraParameters & params, const float f, const float n,
CameraView::CameraView(const std::string cam_name, const camera::CameraParameters& params, const float f, const float n,
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
CameraView::CameraView(const std::string cam_name, const camera::CameraParameters& params, const float f, const float n,
CameraView::CameraView(const std::string& cam_name, const camera::CameraParameters& params, const float f, const float n,

const geometry_msgs::Transform::ConstPtr cam_transform)
: camera::CameraModel(params), f_(f), n_(n) {

: cam_name_(cam_name), camera::CameraModel(params), f_(f), n_(n) {
// Get relative camera position
if (cam_transform == NULL) {
// Create a transform buffer to listen for transforms
Expand Down Expand Up @@ -147,7 +146,7 @@ bool CameraView::InsideTarget(std::vector<int> vert_x, std::vector<int> vert_y,
double size_y) {
// Create depth cam camera model
static camera::CameraParameters depth_cam_params(&cfg_cam_, (depth_cam_name + "_cam").c_str());
CameraView depth_cam(depth_cam_params, f_, n_);
CameraView depth_cam(depth_cam_name, depth_cam_params, f_, n_);

// Get most recent depth message
std::string cam_prefix = TOPIC_HARDWARE_PICOFLEXX_PREFIX;
Expand Down
10 changes: 6 additions & 4 deletions astrobee/behaviors/inspection/src/inspection.cc
Original file line number Diff line number Diff line change
Expand Up @@ -436,8 +436,9 @@ bool Inspection::GenerateAnomalySurvey(geometry_msgs::PoseArray &points_anomaly)
curr_camera_ = cam_name.c_str();
if (cameras_.find(cam_name) == cameras_.end()) {
static camera::CameraParameters cam_params(&cfg_cam_, cam_name.c_str());
cameras_.emplace(std::piecewise_construct, std::make_tuple(cam_name),
std::make_tuple(cam_params, cfg_->Get<double>("max_distance"), cfg_->Get<double>("min_distance")));
cameras_.emplace(
std::piecewise_construct, std::make_tuple(cam_name),
std::make_tuple(cam_name, cam_params, cfg_->Get<double>("max_distance"), cfg_->Get<double>("min_distance")));
}


Expand Down Expand Up @@ -523,8 +524,9 @@ bool Inspection::GeneratePanoramaSurvey(geometry_msgs::PoseArray &points_panoram
curr_camera_ = cam_name.c_str();
if (cameras_.find(cam_name) == cameras_.end()) {
static camera::CameraParameters cam_params(&cfg_cam_, cam_name.c_str());
cameras_.emplace(std::piecewise_construct, std::make_tuple(cam_name),
std::make_tuple(cam_params, cfg_->Get<double>("max_distance"), cfg_->Get<double>("min_distance")));
cameras_.emplace(
std::piecewise_construct, std::make_tuple(cam_name),
std::make_tuple(cam_name, cam_params, cfg_->Get<double>("max_distance"), cfg_->Get<double>("min_distance")));
}

geometry_msgs::PoseArray panorama_relative;
Expand Down
2 changes: 1 addition & 1 deletion pano/pano_view/tools/find_point_coordinate.cc
Original file line number Diff line number Diff line change
Expand Up @@ -215,7 +215,7 @@ int main(int argc, char** argv) {
new geometry_msgs::Transform(msg_conversions::eigen_transform_to_ros_transform(transform_body_to_cam)));

camera::CameraParameters cam_params(&config, camera_name.c_str());
inspection::CameraView camera(cam_params, 2.0, 0.19, msg_pointer);
inspection::CameraView camera(camera_name.c_str(), cam_params, 2.0, 0.19, msg_pointer);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
inspection::CameraView camera(camera_name.c_str(), cam_params, 2.0, 0.19, msg_pointer);
inspection::CameraView camera(camera_name, cam_params, 2.0, 0.19, msg_pointer);

(Converting to char * shouldn't be needed here unless I missed something.)

camera.SetTransform((msg_conversions::ros_pose_to_eigen_transform(ground_truth) * transform_body_to_cam).inverse());


Expand Down