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 smart pointers #1

Open
wants to merge 1 commit into
base: trusty-tahr-indigo-dev
Choose a base branch
from
Open
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
18 changes: 9 additions & 9 deletions source/dbrt/kinematics_from_urdf.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ KinematicsFromURDF::KinematicsFromURDF(

// create segment map for correct ordering of joints
segment_map_ = kin_tree_.getSegments();
boost::shared_ptr<const urdf::Joint> joint;
std::shared_ptr<const urdf::Joint> joint;
joint_map_.resize(kin_tree_.getNrOfJoints());
for (KDL::SegmentMap::const_iterator seg_it = segment_map_.begin();
seg_it != segment_map_.end();
Expand Down Expand Up @@ -145,7 +145,7 @@ void KinematicsFromURDF::inject_offset_joints_and_links(
for (int i = 0; i < dofs.size(); ++i)
{
// construct joint
auto joint = boost::make_shared<urdf::Joint>();
auto joint = std::make_shared<urdf::Joint>();
joint->name = dofs[i] + "_JOINT";
joint->type = i < 3 ? urdf::Joint::PRISMATIC : urdf::Joint::REVOLUTE;
joint->axis.x = double(i == 0 || i == 3);
Expand All @@ -163,7 +163,7 @@ void KinematicsFromURDF::inject_offset_joints_and_links(
// last dof has no link
if (i > 4) continue;

auto link = boost::make_shared<urdf::Link>();
auto link = std::make_shared<urdf::Link>();
link->name = dofs[i] + "_LINK";
link->parent_joint = joint;

Expand All @@ -177,7 +177,7 @@ void KinematicsFromURDF::inject_offset_joints_and_links(
camera_root_link->child_links.push_back(urdf.links_[dofs[0] + "_LINK"]);

// add leaf original camera frame
auto camera_leaf_link = boost::make_shared<urdf::Link>();
auto camera_leaf_link = std::make_shared<urdf::Link>();
camera_leaf_link->name = camera_frame;
camera_leaf_link->parent_joint = urdf.joints_[dofs[5] + "_JOINT"];
urdf.links_[camera_frame] = camera_leaf_link;
Expand Down Expand Up @@ -208,16 +208,16 @@ KinematicsFromURDF::~KinematicsFromURDF()
}

void KinematicsFromURDF::get_part_meshes(
std::vector<boost::shared_ptr<PartMeshModel>>& part_meshes)
std::vector<std::shared_ptr<PartMeshModel>>& part_meshes)
{
// Load robot mesh for each link
std::vector<boost::shared_ptr<urdf::Link>> links;
std::vector<std::shared_ptr<urdf::Link>> links;
urdf_.getLinks(links);
std::string global_root = urdf_.getRoot()->name;
for (unsigned i = 0; i < links.size(); i++)
{
// keep only the links descending from our root
boost::shared_ptr<urdf::Link> tmp_link = links[i];
std::shared_ptr<urdf::Link> tmp_link = links[i];
while (tmp_link->name.compare(rendering_root_left_) == 0 &&
tmp_link->name.compare(rendering_root_right_) == 0 &&
tmp_link->name.compare(global_root) == 0)
Expand All @@ -227,7 +227,7 @@ void KinematicsFromURDF::get_part_meshes(

if (tmp_link->name.compare(global_root) == 0) continue;

boost::shared_ptr<PartMeshModel> part_ptr(
std::shared_ptr<PartMeshModel> part_ptr(
new PartMeshModel(links[i], description_path_, i, false));

if (part_ptr->proper_) // if the link has an actual mesh file to read
Expand Down Expand Up @@ -313,7 +313,7 @@ void KinematicsFromURDF::print_joints()

void KinematicsFromURDF::print_links()
{
std::vector<boost::shared_ptr<urdf::Link>> links;
std::vector<std::shared_ptr<urdf::Link>> links;
urdf_.getLinks(links);

std::cout << "robot links: " << std::endl;
Expand Down
2 changes: 1 addition & 1 deletion source/dbrt/kinematics_from_urdf.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ class KinematicsFromURDF

std::vector<int> get_joint_order(const sensor_msgs::JointState& state);
void get_part_meshes(
std::vector<boost::shared_ptr<PartMeshModel>>& part_meshes);
std::vector<std::shared_ptr<PartMeshModel>>& part_meshes);
KDL::Tree get_tree();

int num_joints();
Expand Down
18 changes: 9 additions & 9 deletions source/dbrt/part_mesh_model.h
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@
class PartMeshModel
{
public:
PartMeshModel(const boost::shared_ptr<urdf::Link> p_link,
PartMeshModel(const std::shared_ptr<urdf::Link> p_link,
const std::string& p_description_path,
unsigned p_index,
bool collision)
Expand All @@ -67,7 +67,7 @@ class PartMeshModel
indices_(new std::vector<std::vector<int>>)
{
// get link shape and origin -------------------------------------------
boost::shared_ptr<urdf::Geometry> geometry;
std::shared_ptr<urdf::Geometry> geometry;
urdf::Pose origin;
if(collision && link_->collision)
{
Expand All @@ -85,8 +85,8 @@ class PartMeshModel
}

// get mesh path -------------------------------------------------------
boost::shared_ptr<urdf::Mesh> mesh =
boost::dynamic_pointer_cast<urdf::Mesh>(geometry);
std::shared_ptr<urdf::Mesh> mesh =
std::dynamic_pointer_cast<urdf::Mesh>(geometry);
boost::filesystem::path filename(mesh->filename);
filename_ = filename.string();

Expand Down Expand Up @@ -147,7 +147,7 @@ class PartMeshModel
proper_ = true;
}

boost::shared_ptr<std::vector<Eigen::Vector3d>> get_vertices()
std::shared_ptr<std::vector<Eigen::Vector3d>> get_vertices()
{
const struct aiMesh* mesh = scene_->mMeshes[0];
unsigned num_vertices = mesh->mNumVertices;
Expand All @@ -163,7 +163,7 @@ class PartMeshModel
return vertices_;
}

boost::shared_ptr<std::vector<std::vector<int>>> get_indices()
std::shared_ptr<std::vector<std::vector<int>>> get_indices()
{
const struct aiMesh* mesh = scene_->mMeshes[0];
unsigned num_faces = mesh->mNumFaces;
Expand Down Expand Up @@ -193,12 +193,12 @@ class PartMeshModel
bool proper_;

private:
const boost::shared_ptr<urdf::Link> link_;
const std::shared_ptr<urdf::Link> link_;
const struct aiScene* scene_;
unsigned numFaces_;

boost::shared_ptr<std::vector<Eigen::Vector3d>> vertices_;
boost::shared_ptr<std::vector<std::vector<int>>> indices_;
std::shared_ptr<std::vector<Eigen::Vector3d>> vertices_;
std::shared_ptr<std::vector<std::vector<int>>> indices_;

Eigen::Affine3d original_transform_;

Expand Down
2 changes: 1 addition & 1 deletion source/dbrt/urdf_object_loader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ void UrdfObjectModelLoader::load(
std::vector<std::vector<Eigen::Vector3d>>& vertices,
std::vector<std::vector<std::vector<int>>>& triangle_indices) const
{
std::vector<boost::shared_ptr<PartMeshModel>> part_meshes_;
std::vector<std::shared_ptr<PartMeshModel>> part_meshes_;
urdf_kinematics_->get_part_meshes(part_meshes_);

if(part_meshes_.size() == 0)
Expand Down
2 changes: 1 addition & 1 deletion source/dbrt/util/robot_emulator.h
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ class RobotEmulator
// camera publisher
pub_camera_info_ = node_handle_.advertise<sensor_msgs::CameraInfo>(
prefix + "/XTION/depth/camera_info", 0);
boost::shared_ptr<image_transport::ImageTransport> it(
std::shared_ptr<image_transport::ImageTransport> it(
new image_transport::ImageTransport(node_handle_));
pub_depth_image_ = it->advertise(prefix + "/XTION/depth/image", 0);
}
Expand Down