From 900fd86d58087dfe7bd913aee707562699f7eab9 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Mon, 29 Aug 2016 12:35:02 -0700 Subject: [PATCH] fix R2D2GraspExample --- data/kiva_shelf/model.sdf | 4 ++-- examples/RoboticsLearning/R2D2GraspExample.cpp | 6 ++---- examples/RoboticsLearning/b3RobotSimAPI.h | 1 + 3 files changed, 5 insertions(+), 6 deletions(-) diff --git a/data/kiva_shelf/model.sdf b/data/kiva_shelf/model.sdf index b1f49e66b..3e506a9b0 100644 --- a/data/kiva_shelf/model.sdf +++ b/data/kiva_shelf/model.sdf @@ -2,10 +2,10 @@ 1 - 0 2 1.21 0 0 0 + 0 2 0 0 0 0 - 0.0 0.0 1.2045 0 0 0 + 0.0 .0 1.2045 0 0 0 76.26 47 diff --git a/examples/RoboticsLearning/R2D2GraspExample.cpp b/examples/RoboticsLearning/R2D2GraspExample.cpp index 4da5cc22a..a83d4976f 100644 --- a/examples/RoboticsLearning/R2D2GraspExample.cpp +++ b/examples/RoboticsLearning/R2D2GraspExample.cpp @@ -94,11 +94,9 @@ public: { b3RobotSimLoadFileArgs args(""); args.m_fileName = "kiva_shelf/model.sdf"; - args.m_startPosition.setValue(0,0,.5); - args.m_startOrientation = b3Quaternion(0,B3_HALF_PI,0); - args.m_forceOverrideFixedBase = true; + args.m_forceOverrideFixedBase = true; args.m_fileType = B3_SDF_FILE; - //args.m_startOrientation = b3Quaternion() + args.m_startOrientation = b3Quaternion(0,0,0,1); b3RobotSimLoadFileResults results; m_robotSim.loadFile(args,results); } diff --git a/examples/RoboticsLearning/b3RobotSimAPI.h b/examples/RoboticsLearning/b3RobotSimAPI.h index 88506e871..5070b0155 100644 --- a/examples/RoboticsLearning/b3RobotSimAPI.h +++ b/examples/RoboticsLearning/b3RobotSimAPI.h @@ -32,6 +32,7 @@ struct b3RobotSimLoadFileArgs m_startPosition(b3MakeVector3(0,0,0)), m_startOrientation(b3Quaternion(0,0,0,1)), m_forceOverrideFixedBase(false), + m_useMultiBody(true), m_fileType(B3_URDF_FILE) { }