Commit b6aedae0 authored by jcarpent's avatar jcarpent
Browse files

Move romeo models to a dedicated directory

parent c0ec9405
......@@ -18,8 +18,8 @@ class TestFrameBindings(unittest.TestCase):
m4ones = eye(4)
current_file = os.path.dirname(os.path.abspath(__file__))
pinocchio_models_dir = os.path.abspath(os.path.join(current_file, '../models'))
romeo_model_path = os.path.abspath(os.path.join(current_file, '../models/romeo.urdf'))
pinocchio_models_dir = os.path.abspath(os.path.join(current_file, '../models/romeo'))
romeo_model_path = os.path.abspath(os.path.join(pinocchio_mdoels_dir, '/urdf/romeo.urdf'))
hint_list = [pinocchio_models_dir, "wrong/hint"] # hint list
robot = RobotWrapper(romeo_model_path, hint_list, se3.JointModelFreeFlyer())
......
......@@ -19,8 +19,8 @@ class TestGeometryObjectBindings(unittest.TestCase):
current_file = os.path.dirname(os.path.abspath(__file__))
pinocchio_models_dir = os.path.abspath(os.path.join(current_file, '../models'))
romeo_model_path = os.path.abspath(os.path.join(current_file, '../models/romeo.urdf'))
pinocchio_models_dir = os.path.abspath(os.path.join(current_file, '../models/romeo'))
romeo_model_path = os.path.abspath(pinocchio_models_dir, '/urdf/romeo.urdf')
hint_list = [pinocchio_models_dir, "wrong/hint"] # hint list
robot = RobotWrapper(romeo_model_path, hint_list, se3.JointModelFreeFlyer())
......
......@@ -6,8 +6,8 @@ import os
from pinocchio.robot_wrapper import RobotWrapper
# Warning : the paths are here hard-coded. This file is only here as an example
romeo_model_path = os.path.abspath(os.path.join(current_file, '../models'))
romeo_model_file = romeo_model_path + "/romeo.urdf"
romeo_model_path = os.path.abspath(os.path.join(current_file, '../models/romeo'))
romeo_model_file = romeo_model_path + "/urdf/romeo.urdf"
list_hints = [romeo_model_path,"titi"]
robot = RobotWrapper(romeo_model_file,list_hints, se3.JointModelFreeFlyer())
......
......@@ -218,9 +218,9 @@ BOOST_AUTO_TEST_CASE ( loading_model )
typedef se3::GeometryData GeometryData;
std::string filename = PINOCCHIO_SOURCE_DIR"/models/romeo.urdf";
std::string filename = PINOCCHIO_SOURCE_DIR"/models/romeo/urdf/romeo.urdf";
std::vector < std::string > packageDirs;
std::string meshDir = PINOCCHIO_SOURCE_DIR"/models/";
std::string meshDir = PINOCCHIO_SOURCE_DIR"/models/romeo/";
packageDirs.push_back(meshDir);
Model model;
......@@ -252,8 +252,8 @@ BOOST_AUTO_TEST_CASE (radius)
std::string filename = ROMEO_DESCRIPTION_MODEL_DIR"/romeo_description/urdf/romeo_small.urdf";
packageDirs.push_back(ROMEO_DESCRIPTION_MODEL_DIR);
#else
std::string filename = PINOCCHIO_SOURCE_DIR"/models/romeo.urdf";
std::string meshDir = PINOCCHIO_SOURCE_DIR"/models/";
std::string filename = PINOCCHIO_SOURCE_DIR"/models/romeo/urdf/romeo.urdf";
std::string meshDir = PINOCCHIO_SOURCE_DIR"/models/romeo/";
packageDirs.push_back(meshDir);
#endif // ROMEO_DESCRIPTION_MODEL_DIR
......@@ -329,8 +329,8 @@ BOOST_AUTO_TEST_CASE ( romeo_joints_meshes_positions )
std::string filename = ROMEO_DESCRIPTION_MODEL_DIR"/romeo_description/urdf/romeo_small.urdf";
packageDirs.push_back(ROMEO_DESCRIPTION_MODEL_DIR);
#else
std::string filename = PINOCCHIO_SOURCE_DIR"/models/romeo.urdf";
std::string meshDir = PINOCCHIO_SOURCE_DIR"/models/";
std::string filename = PINOCCHIO_SOURCE_DIR"/models/romeo/urdf/romeo.urdf";
std::string meshDir = PINOCCHIO_SOURCE_DIR"/models/romeo/";
packageDirs.push_back(meshDir);
#endif // ROMEO_DESCRIPTION_MODEL_DIR
......@@ -439,8 +439,8 @@ BOOST_AUTO_TEST_CASE ( hrp2_mesh_distance)
std::string filename = ROMEO_DESCRIPTION_MODEL_DIR"/romeo_description/urdf/romeo_small.urdf";
packageDirs.push_back(ROMEO_DESCRIPTION_MODEL_DIR);
#else
std::string filename = PINOCCHIO_SOURCE_DIR"/models/romeo.urdf";
std::string meshDir = PINOCCHIO_SOURCE_DIR"/models/";
std::string filename = PINOCCHIO_SOURCE_DIR"/models/romeo/urdf/romeo.urdf";
std::string meshDir = PINOCCHIO_SOURCE_DIR"/models/romeo/";
packageDirs.push_back(meshDir);
#endif // ROMEO_DESCRIPTION_MODEL_DIR
......
Supports Markdown
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment