Skip to content
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
4 changes: 1 addition & 3 deletions .travis.sh
Original file line number Diff line number Diff line change
Expand Up @@ -75,10 +75,8 @@ catkin build --limit-status-rate 0.1 --no-notify -DCMAKE_BUILD_TYPE=Release
# Build tests
catkin build --limit-status-rate 0.1 --no-notify --make-args tests
# Run tests
####### kinteic has problem on runnning gazebo with image on headless mode????
if [ "$CI_ROS_DISTRO" == "kinetic" ]; then
####### avoid problem on runnning gazebo with image on headless mode????
touch src/rtmros_nextage/nextage_calibration/CATKIN_IGNORE
fi
#######
catkin run_tests -j1 -p1
# check test (this only works from indigo onward)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
name="spawn_sensor_kinect"
type="spawn_model"
args="-urdf -param sensor_description -model sensor_kinect
-reference_frame HEAD_JOINT1_Link -P 1.5708 -x -0.15 -z 0.05"
-reference_frame HEAD_JOINT1_Link -P 1.5708 -x 0.15 -z 0.15"
/>

<node pkg="robot_state_publisher"
Expand All @@ -27,6 +27,6 @@
<node name="spawn_checkerboard_chest" pkg="gazebo_ros" type="spawn_model"
args="-file $(find nextage_calibration)/models/checkerboard_horizontal.urdf
-urdf -model checkerboard_horizontal
-reference_frame WAIST -wait" />
-reference_frame WAIST" />

</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
name="spawn_sensor_kinect"
type="spawn_model"
args="-urdf -param sensor_description -model sensor_kinect
-reference_frame HEAD_JOINT1_Link -P 1.5708 -x -0.15 -z 0.05"
-reference_frame HEAD_JOINT1_Link -P 1.5708 -x 0.15 -z 0.15"
/>

<node pkg="robot_state_publisher"
Expand All @@ -27,6 +27,6 @@
<node name="spawn_checkerboard_waist" pkg="gazebo_ros" type="spawn_model"
args="-file $(find nextage_calibration)/models/checkerboard_waist.urdf
-urdf -model checkerboard_waist
-reference_frame WAIST -wait" />
-reference_frame WAIST" />

</launch>
6 changes: 4 additions & 2 deletions nextage_calibration/models/sensor_kinect.xacro
Original file line number Diff line number Diff line change
@@ -1,8 +1,10 @@
<robot name="sensor_kinect" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:property name="M_PI" value="3.1415926535897931" />
<xacro:include filename="$(find turtlebot_description)/urdf/sensors/kinect.urdf.xacro" />
<xacro:include filename="$(find openni_description)/model/kinect.urdf.xacro" />
<link name="camera_base_link" />
<xacro:sensor_kinect parent="camera_base_link" />
<xacro:sensor_kinect parent="camera_base_link"
cam_px="0.0" cam_py="0.0" cam_pz="0.0"
cam_or="0.0" cam_op="0.0" cam_oy="0.0" />
<gazebo>
<static>true</static>
</gazebo>
Expand Down
4 changes: 3 additions & 1 deletion nextage_calibration/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,9 @@
<run_depend>openni2_launch</run_depend>
<run_depend>tf</run_depend>
<run_depend>urdf</run_depend>
<run_depend>turtlebot_description</run_depend> <!-- TODO This needs better solution https://github.com/tork-a/rtmros_nextage/issues/314 -->
<run_depend>openni_camera</run_depend>
<run_depend>openni_description</run_depend>
<run_depend>openni_launch</run_depend>

<test_depend>nextage_gazebo</test_depend>

Expand Down
1 change: 1 addition & 0 deletions nextage_description/urdf/NextageOpen.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -500,6 +500,7 @@
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/</robotNamespace>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
<legacyModeNS>true</legacyModeNS>
</plugin>
</gazebo>

Expand Down