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

camera_info_manager: Adding public member function to manually set camera_info #20

Merged
merged 1 commit into from
May 18, 2014
Merged
Show file tree
Hide file tree
Changes from all 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
Original file line number Diff line number Diff line change
Expand Up @@ -185,6 +185,7 @@ class CameraInfoManager
std::string resolveURL(const std::string &url,
const std::string &cname);
bool setCameraName(const std::string &cname);
bool setCameraInfo(const sensor_msgs::CameraInfo &camera_info);
bool validateURL(const std::string &url);

private:
Expand Down Expand Up @@ -214,8 +215,8 @@ class CameraInfoManager
bool saveCalibrationFile(const sensor_msgs::CameraInfo &new_info,
const std::string &filename,
const std::string &cname);
bool setCameraInfo(sensor_msgs::SetCameraInfo::Request &req,
sensor_msgs::SetCameraInfo::Response &rsp);
bool setCameraInfoService(sensor_msgs::SetCameraInfo::Request &req,
sensor_msgs::SetCameraInfo::Response &rsp);

/** @brief mutual exclusion lock for private data
*
Expand Down
26 changes: 22 additions & 4 deletions camera_info_manager/src/camera_info_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ CameraInfoManager::CameraInfoManager(ros::NodeHandle nh,
{
// register callback for camera calibration service request
info_service_ = nh_.advertiseService("set_camera_info",
&CameraInfoManager::setCameraInfo, this);
&CameraInfoManager::setCameraInfoService, this);
}

/** Get the current CameraInfo data.
Expand All @@ -105,7 +105,7 @@ CameraInfoManager::CameraInfoManager(ros::NodeHandle nh,
*/
sensor_msgs::CameraInfo CameraInfoManager::getCameraInfo(void)
{
while (true)
while (ros::ok())
{
std::string cname;
std::string url;
Expand Down Expand Up @@ -553,8 +553,8 @@ CameraInfoManager::saveCalibrationFile(const sensor_msgs::CameraInfo &new_info,
* @return true if message handled
*/
bool
CameraInfoManager::setCameraInfo(sensor_msgs::SetCameraInfo::Request &req,
sensor_msgs::SetCameraInfo::Response &rsp)
CameraInfoManager::setCameraInfoService(sensor_msgs::SetCameraInfo::Request &req,
sensor_msgs::SetCameraInfo::Response &rsp)
{
// copies of class variables needed for saving calibration
std::string url_copy;
Expand Down Expand Up @@ -617,6 +617,24 @@ bool CameraInfoManager::setCameraName(const std::string &cname)
return true;
}

/** Set the camera info manually
*
* @param camera_info new camera calibration data
*
* @return true if new camera info is set
*
* @post @c cam_info_ updated, if valid;
Copy link
Contributor Author

Choose a reason for hiding this comment

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

I guess technically there's no validity check here. We could make sure the parameters are all reasonable, could potentially catch errors.

Copy link
Member

Choose a reason for hiding this comment

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

As an API, it at least gives us the option to add various checks if a good reason for them arises.

*/
bool CameraInfoManager::setCameraInfo(const sensor_msgs::CameraInfo &camera_info)
{
boost::mutex::scoped_lock lock(mutex_);

cam_info_ = camera_info;
loaded_cam_info_ = true;

return true;
}

/** Validate URL syntax.
*
* @param url Uniform Resource Locator to check
Expand Down