diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml index 25685c7602c1010fd9242ab2cc87153b07ed87da..2cf95b32b7edf1fdcf2eea8086ccba9524bd1529 100644 --- a/.gitlab-ci.yml +++ b/.gitlab-ci.yml @@ -1,56 +1 @@ -# Please don't edit this file, and use the version generated at -# http://rainboard.laas.fr/project/talos_data/.gitlab-ci.yml - -variables: - GIT_SUBMODULE_STRATEGY: "recursive" - CCACHE_BASEDIR: "${CI_PROJECT_DIR}" - CCACHE_DIR: "${CI_PROJECT_DIR}/ccache" - -cache: - paths: - - ccache - -.robotpkg-talos-data: &robotpkg-talos-data - except: - - gh-pages - script: - - mkdir -p ccache - - cd /root/robotpkg/wip - - git pull - - cd talos-data - - make checkout MASTER_REPOSITORY="git ${CI_PROJECT_DIR}/.git" - - make install - - cd $(make show-var VARNAME=WRKSRC) - - make test - -robotpkg-talos-data-14.04-release: - <<: *robotpkg-talos-data - image: gepgitlab.laas.fr:4567/pyrene-dev/talos_data/talos-data:14.04 - -robotpkg-talos-data-16.04-release: - <<: *robotpkg-talos-data - image: gepgitlab.laas.fr:4567/pyrene-dev/talos_data/talos-data:16.04 - -robotpkg-talos-data-18.04-release: - <<: *robotpkg-talos-data - image: gepgitlab.laas.fr:4567/pyrene-dev/talos_data/talos-data:18.04 - -doc-coverage: - <<: *robotpkg-talos-data - image: gepgitlab.laas.fr:4567/pyrene-dev/talos_data/talos-data:16.04 - before_script: - - echo -e 'CXXFLAGS+= --coverage\nLDFLAGS+= --coverage\nPKG_DEFAULT_OPTIONS= debug' >> /opt/openrobots/etc/robotpkg.conf - after_script: - - cd /root/robotpkg/wip/talos-data - - cd $(make show-var VARNAME=WRKSRC) - - make doc - - mv doc/doxygen-html ${CI_PROJECT_DIR} - - mkdir -p ${CI_PROJECT_DIR}/coverage/ - - gcovr -r . - - gcovr -r . --html --html-details -o ${CI_PROJECT_DIR}/coverage/index.html - artifacts: - expire_in: 1 day - paths: - - doxygen-html/ - - coverage/ - +include: http://rainboard.laas.fr/project/talos_data/.gitlab-ci.yml diff --git a/CMakeLists.txt b/CMakeLists.txt index 666ff8fedb4a4ae3c0a67f0955b90686eb2ff783..48d910d3f9ad8b7db93a5e997d726be156e4f0bb 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -2,10 +2,10 @@ CMAKE_MINIMUM_REQUIRED(VERSION 2.8.3) INCLUDE(cmake/base.cmake) #include(cmake/ros.cmake) - +SET(PROJECT_ORG pyrene-dev) SET(PROJECT_NAME talos_data) SET(PROJECT_DESCRIPTION "Talos urdf model, srdf model and other data") -SET(PROJECT_URL "https://redmine.laas.fr/projects/pyrene-talos/repository/talos-data") +SET(PROJECT_URL "https://gepgitlab.laas.fr/${PROJECT_ORG}/${PROJECT_NAME}") set(CXX_DISABLE_WERROR True) SETUP_PROJECT() diff --git a/cmake b/cmake index 6ccc9f9b2a2ff510ae7754c515c72f8e38410447..4c358432cc006d040a2ccd4ef5c5de9f5d0d87c2 160000 --- a/cmake +++ b/cmake @@ -1 +1 @@ -Subproject commit 6ccc9f9b2a2ff510ae7754c515c72f8e38410447 +Subproject commit 4c358432cc006d040a2ccd4ef5c5de9f5d0d87c2 diff --git a/srdf/talos.srdf b/srdf/talos.srdf index 331da5015bce66ffb15ab962d51bd23c55aadaf9..a579ef35d7acc01b80cde056f3550d35c1df3735 100644 --- a/srdf/talos.srdf +++ b/srdf/talos.srdf @@ -129,6 +129,7 @@ <!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'--> <group_state name="half_sitting" group="all"> + <joint name="root_joint" value="0. 0. 1.01927 0. 0. 0. 1." /> <joint name="arm_left_1_joint" value="0.25847" /> <joint name="arm_left_2_joint" value="0.173046" /> <joint name="arm_left_3_joint" value="-0.0002" /> diff --git a/urdf/talos_reduced.urdf b/urdf/talos_reduced.urdf index 56bbdfe1b0d9ac9d7a9568b7e67925acd345918e..3f912160d996a4c293957283eeb1abdc25a7649f 100644 --- a/urdf/talos_reduced.urdf +++ b/urdf/talos_reduced.urdf @@ -2184,21 +2184,20 @@ </geometry> <material name="Grey"/> </visual> + <collision> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://talos_data/meshes/v2/ankle_X_collision.stl" scale="1 1 1"/> + </geometry> + </collision> <!-- - <collision> - <origin xyz="0 0 0" rpy="0 0 0" /> - <geometry> - <mesh filename="package://talos_data/meshes/v2/ankle_X_collision.stl" scale="1 ${reflect*1} 1"/> - </geometry> - </collision> - - --> <collision> <origin rpy="0 0 0" xyz="0 0 -0.1"/> <geometry> <box size="0.21 0.13 0.02"/> </geometry> </collision> + --> </link> <joint name="leg_left_6_joint" type="revolute"> <parent link="leg_left_5_link"/> @@ -2510,21 +2509,20 @@ </geometry> <material name="Grey"/> </visual> + <collision> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://talos_data/meshes/v2/ankle_X_collision.stl" scale="1 -1 1"/> + </geometry> + </collision> <!-- - <collision> - <origin xyz="0 0 0" rpy="0 0 0" /> - <geometry> - <mesh filename="package://talos_data/meshes/v2/ankle_X_collision.stl" scale="1 ${reflect*1} 1"/> - </geometry> - </collision> - - --> <collision> <origin rpy="0 0 0" xyz="0 0 -0.1"/> <geometry> <box size="0.21 0.13 0.02"/> </geometry> </collision> + --> </link> <joint name="leg_right_6_joint" type="revolute"> <parent link="leg_right_5_link"/>