48 #include <Rcs_typedef.h> 49 #include <Rcs_macros.h> 51 #ifdef GRAPHICS_AVAILABLE 53 #include <RcsViewer.h> 70 std::string actionModelType =
"unspecified";
73 if (actionModelType ==
"joint_acc") {
78 double max_action = 1314.52/10.;
86 std::ostringstream os;
87 os <<
"Unsupported action model type: " << actionModelType;
88 throw std::invalid_argument(os.str());
116 RcsBody* arm = RcsGraph_getBodyByName(
graph,
"Arm");
117 RcsBody* pendulum = RcsGraph_getBodyByName(
graph,
"Pendulum");
123 #ifdef GRAPHICS_AVAILABLE 124 viewer->setCameraHomePosition(osg::Vec3d(0.7, 0.7, 0.4),
125 osg::Vec3d(-0.2, -0.2, 0.0),
126 osg::Vec3d(0.0, 0.05, 1.0));
131 std::vector<std::string>& linesOut,
double currentTime,
const MatNd* obs,
const MatNd* currentAction,
135 const char* simName =
"None";
136 if (simulator != NULL) {
137 simName = simulator->getClassName();
141 linesOut.emplace_back(
143 simName, currentTime));
145 unsigned int numPosCtrlJoints = 0;
146 unsigned int numTrqCtrlJoints = 0;
148 RCSGRAPH_TRAVERSE_JOINTS(
graph) {
149 if (JNT->jacobiIndex != -1) {
150 if (JNT->ctrlType == RCSJOINT_CTRL_TYPE::RCSJOINT_CTRL_POSITION) {
153 else if (JNT->ctrlType == RCSJOINT_CTRL_TYPE::RCSJOINT_CTRL_TORQUE) {
158 linesOut.emplace_back(
159 string_format(
"num joints: %d total, %d pos ctrl, %d trq ctrl",
graph->nJ, numPosCtrlJoints,
162 linesOut.emplace_back(
164 RCS_RAD2DEG(obs->ele[0]), RCS_RAD2DEG(obs->ele[1])));
166 const double* distForce = forceDisturber->
getLastForce();
167 linesOut.emplace_back(
169 distForce[0], distForce[1], distForce[2]));
171 std::stringstream ss;
173 for (
unsigned int i = 0; i < currentAction->m - 1; i++) {
174 ss << std::fixed << std::setprecision(3) << MatNd_get(currentAction, i, 0) <<
", ";
179 ss << std::fixed << std::setprecision(3) << MatNd_get(currentAction, currentAction->m - 1, 0) <<
"]";
182 if (physicsManager != NULL) {
186 RcsBody* arm = RcsGraph_getBodyByName(
graph,
"Arm");
187 RcsBody* pendulum = RcsGraph_getBodyByName(
graph,
"Pendulum");
191 "arm mass: %1.3f kg pendulum mass: %1.3f kg",
192 arm->m, pendulum->m));
195 "arm length: %1.3f m pendulum length: %1.3f m",
196 arm->shape[0]->extents[2], pendulum->shape[0]->extents[2]));
199 "arm radius: %1.3f m pendulum radius: %1.3f m",
200 arm->shape[0]->extents[0], pendulum->shape[0]->extents[0]));
virtual bool getProperty(std::string &out, const char *property)=0
virtual ObservationModel * createObservationModel()
void getHUDText(std::vector< std::string > &linesOut, double currentTime, const MatNd *obs, const MatNd *currentAction, PhysicsBase *simulator, PhysicsParameterManager *physicsManager, ForceDisturber *forceDisturber) override
virtual InitStateSetter * createInitStateSetter()
virtual void populatePhysicsParameters(PhysicsParameterManager *manager)
virtual ForceDisturber * createForceDisturber()
void addParam(const char *bodyName, PhysicsParameterDescriptor *desc)
const double * getLastForce() const
static ObservationModel * observeAllJoints(RcsGraph *graph)
virtual ActionModel * createActionModel()
virtual void initViewer(Rcs::Viewer *viewer)
std::string string_format(const std::string &format, Args ... args)
PropertySource * properties
Property source (owned)
static ExperimentConfigRegistration< ECQuanserQube > RegQuanserQube("QuanserQube")
RcsGraph * graph
Graph description.