Skip to content

Commit

Permalink
Merge branch 'master' of https://github.com/ilpincy/argos3
Browse files Browse the repository at this point in the history
  • Loading branch information
ilpincy committed Nov 9, 2019
2 parents b666cad + b2e97d2 commit 0dae5fa
Show file tree
Hide file tree
Showing 11 changed files with 307 additions and 28 deletions.
4 changes: 4 additions & 0 deletions src/core/real_robot/real_robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,11 @@ void CRealRobot::Init(const std::string& str_conf_fname,
* Initialize the controller
*/
LOG << "[INFO] Controller type '" << strControllerTag << "', id '" << str_controller_id << "' initialization start" << std::endl;
#ifdef ARGOS_DYNAMIC_LIBRARY_LOADING
m_pcController = CFactory<CCI_Controller>::New(strControllerTag);
#else
m_pcController = ControllerMaker(strControllerTag);
#endif
/* Set the controller id using the machine hostname */
char pchHostname[256];
pchHostname[255] = '\0';
Expand Down
5 changes: 4 additions & 1 deletion src/plugins/robots/e-puck/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@ set(ARGOS3_HEADERS_PLUGINS_ROBOTS_EPUCK_CONTROLINTERFACE
if(ARGOS_BUILD_FOR_SIMULATOR)
set(ARGOS3_HEADERS_PLUGINS_ROBOTS_EPUCK_SIMULATOR
simulator/dynamics2d_epuck_model.h
simulator/dynamics3d_epuck_model.h
# simulator/physx_epuck_model.h
simulator/epuck_entity.h
simulator/epuck_proximity_default_sensor.h)
Expand All @@ -23,6 +24,7 @@ if(ARGOS_BUILD_FOR_SIMULATOR)
set(ARGOS3_SOURCES_PLUGINS_ROBOTS_EPUCK
${ARGOS3_SOURCES_PLUGINS_ROBOTS_EPUCK}
${ARGOS3_HEADERS_PLUGINS_ROBOTS_EPUCK_SIMULATOR}
simulator/dynamics3d_epuck_model.cpp
simulator/dynamics2d_epuck_model.cpp
# simulator/physx_epuck_model.cpp
simulator/epuck_entity.cpp
Expand All @@ -45,7 +47,8 @@ endif(ARGOS_BUILD_FOR_SIMULATOR)
add_library(argos3plugin_${ARGOS_BUILD_FOR}_epuck SHARED ${ARGOS3_SOURCES_PLUGINS_ROBOTS_EPUCK})
target_link_libraries(argos3plugin_${ARGOS_BUILD_FOR}_epuck
argos3plugin_${ARGOS_BUILD_FOR}_genericrobot
argos3plugin_${ARGOS_BUILD_FOR}_dynamics2d)
argos3plugin_${ARGOS_BUILD_FOR}_dynamics2d
argos3plugin_${ARGOS_BUILD_FOR}_dynamics3d)
# argos3plugin_${ARGOS_BUILD_FOR}_physx)
if(ARGOS_BUILD_FOR_SIMULATOR AND ARGOS_COMPILE_QTOPENGL)
target_link_libraries(argos3plugin_${ARGOS_BUILD_FOR}_epuck argos3plugin_${ARGOS_BUILD_FOR}_qtopengl)
Expand Down
206 changes: 206 additions & 0 deletions src/plugins/robots/e-puck/simulator/dynamics3d_epuck_model.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,206 @@
/**
* @file <argos3/plugins/robots/e-puck/simulator/dynamics3d_epuck_model.cpp>
*
* @author Michael Allwright - <[email protected]>
*/

#include "dynamics3d_epuck_model.h"

#include <argos3/plugins/simulator/physics_engines/dynamics3d/dynamics3d_engine.h>
#include <argos3/plugins/simulator/physics_engines/dynamics3d/dynamics3d_shape_manager.h>

#include <argos3/plugins/simulator/entities/wheeled_entity.h>
#include <argos3/plugins/robots/e-puck/simulator/epuck_entity.h>

namespace argos {

/****************************************/
/****************************************/

CDynamics3DEPuckModel::CDynamics3DEPuckModel(CDynamics3DEngine& c_engine,
CEPuckEntity& c_epuck) :
/* technically, the CDynamics3DMultiBodyObjectModel should be initialized with 7 children
links, however, setting it to 7 makes the epuck less stable for reasons. */
CDynamics3DMultiBodyObjectModel(c_engine, c_epuck, 3, false),
m_cWheeledEntity(c_epuck.GetWheeledEntity()) {
/* get the required collision shapes */
std::shared_ptr<btCollisionShape> ptrBodyShape =
CDynamics3DShapeManager::RequestBox(m_cBodyHalfExtents);
std::shared_ptr<btCollisionShape> ptrWheelShape =
CDynamics3DShapeManager::RequestCylinder(m_cWheelHalfExtents);
/* calculate the inertia of the collision objects */
btVector3 cBodyInertia;
btVector3 cWheelInertia;
ptrBodyShape->calculateLocalInertia(m_fBodyMass, cBodyInertia);
ptrWheelShape->calculateLocalInertia(m_fWheelMass, cWheelInertia);
/* calculate a btTransform that moves us from the global coordinate system to the
local coordinate system */
const SAnchor& sOriginAnchor = c_epuck.GetEmbodiedEntity().GetOriginAnchor();
const CQuaternion& cOrientation = sOriginAnchor.Orientation;
const CVector3& cPosition = sOriginAnchor.Position;
const btTransform& cStartTransform = btTransform(
btQuaternion(cOrientation.GetX(),
cOrientation.GetZ(),
-cOrientation.GetY(),
cOrientation.GetW()),
btVector3(cPosition.GetX(),
cPosition.GetZ(),
-cPosition.GetY()));
/* create a CAbstractBody::SData structure for each body */
CAbstractBody::SData sBodyData(
cStartTransform * m_cBodyOffset,
m_cBodyGeometricOffset,
cBodyInertia,
m_fBodyMass,
GetEngine().GetDefaultFriction());
CAbstractBody::SData sLeftWheelData(
cStartTransform * m_cLeftWheelOffset,
m_cWheelGeometricOffset,
cWheelInertia,
m_fWheelMass,
m_fWheelFriction);
CAbstractBody::SData sRightWheelData(
cStartTransform * m_cRightWheelOffset,
m_cWheelGeometricOffset,
cWheelInertia,
m_fWheelMass,
m_fWheelFriction);
/* create an anchor for the body (not strictly necessary but easier than
overloading CDynamics3DMultiBodyObjectModel::UpdateOriginAnchor) */
SAnchor* psBodyAnchor = &c_epuck.GetEmbodiedEntity().AddAnchor("body", {0.0, 0.0, 0.00125});
/* create the bodies */
m_ptrBody = std::make_shared<CBase>(*this, psBodyAnchor, ptrBodyShape, sBodyData);
m_ptrLeftWheel = std::make_shared<CLink>(*this, 0, nullptr, ptrWheelShape, sLeftWheelData);
m_ptrRightWheel = std::make_shared<CLink>(*this, 1, nullptr, ptrWheelShape, sRightWheelData);
/* copy the bodies to the base class */
m_vecBodies = {m_ptrBody, m_ptrLeftWheel, m_ptrRightWheel};
/* synchronize with the entity with the space */
Reset();
}

/****************************************/
/****************************************/

void CDynamics3DEPuckModel::Reset() {
/* reset the base class */
CDynamics3DMultiBodyObjectModel::Reset();
/* set up wheels */
m_cMultiBody.setupRevolute(m_ptrLeftWheel->GetIndex(),
m_ptrLeftWheel->GetData().Mass,
m_ptrLeftWheel->GetData().Inertia,
m_ptrBody->GetIndex(),
m_cBodyToLeftWheelJointRotation,
btVector3(0.0, 1.0, 0.0),
m_cBodyToLeftWheelJointOffset,
m_cLeftWheelToBodyJointOffset,
true);
m_cMultiBody.setupRevolute(m_ptrRightWheel->GetIndex(),
m_ptrRightWheel->GetData().Mass,
m_ptrRightWheel->GetData().Inertia,
m_ptrBody->GetIndex(),
m_cBodyToRightWheelJointRotation,
btVector3(0.0, 1.0, 0.0),
m_cBodyToRightWheelJointOffset,
m_cRightWheelToBodyJointOffset,
true);
/* set up motors for the wheels */
m_ptrLeftMotor =
std::make_unique<btMultiBodyJointMotor>(&m_cMultiBody,
m_ptrLeftWheel->GetIndex(),
0.0,
m_fWheelMotorMaxImpulse);
m_ptrRightMotor =
std::make_unique<btMultiBodyJointMotor>(&m_cMultiBody,
m_ptrRightWheel->GetIndex(),
0.0,
m_fWheelMotorMaxImpulse);
/* Allocate memory and prepare the btMultiBody */
m_cMultiBody.finalizeMultiDof();
/* Synchronize with the entity in the space */
UpdateEntityStatus();
}

/****************************************/
/****************************************/

void CDynamics3DEPuckModel::CalculateBoundingBox() {
btVector3 cModelAabbMin, cModelAabbMax;
/* Initialize the bounding box with the base's AABB */
m_ptrBody->GetShape().getAabb(m_ptrBody->GetTransform(), cModelAabbMin, cModelAabbMax);
/* Write back the bounding box swapping the coordinate systems and the Y component */
GetBoundingBox().MinCorner.Set(cModelAabbMin.getX(), -cModelAabbMax.getZ(), cModelAabbMin.getY());
GetBoundingBox().MaxCorner.Set(cModelAabbMax.getX(), -cModelAabbMin.getZ(), cModelAabbMax.getY());
}

/****************************************/
/****************************************/

void CDynamics3DEPuckModel::UpdateEntityStatus() {
/* run the base class's implementation of this method */
CDynamics3DMultiBodyObjectModel::UpdateEntityStatus();
}

/****************************************/
/****************************************/

void CDynamics3DEPuckModel::UpdateFromEntityStatus() {
/* run the base class's implementation of this method */
CDynamics3DMultiBodyObjectModel::UpdateFromEntityStatus();
/* update joint velocities */
m_ptrLeftMotor->setVelocityTarget(m_cWheeledEntity.GetWheelVelocities()[0]);
m_ptrRightMotor->setVelocityTarget(m_cWheeledEntity.GetWheelVelocities()[1]);
}

/****************************************/
/****************************************/

void CDynamics3DEPuckModel::AddToWorld(btMultiBodyDynamicsWorld& c_world) {
/* run the base class's implementation of this method */
CDynamics3DMultiBodyObjectModel::AddToWorld(c_world);
/* add the actuators (btMultiBodyJointMotors) constraints to the world */
c_world.addMultiBodyConstraint(m_ptrLeftMotor.get());
c_world.addMultiBodyConstraint(m_ptrRightMotor.get());
}

/****************************************/
/****************************************/

void CDynamics3DEPuckModel::RemoveFromWorld(btMultiBodyDynamicsWorld& c_world) {
/* remove the actuators (btMultiBodyJointMotors) constraints from the world */
c_world.removeMultiBodyConstraint(m_ptrRightMotor.get());
c_world.removeMultiBodyConstraint(m_ptrLeftMotor.get());
/* run the base class's implementation of this method */
CDynamics3DMultiBodyObjectModel::RemoveFromWorld(c_world);
}

/****************************************/
/****************************************/

REGISTER_STANDARD_DYNAMICS3D_OPERATIONS_ON_ENTITY(CEPuckEntity, CDynamics3DEPuckModel);

/****************************************/
/****************************************/

const btVector3 CDynamics3DEPuckModel::m_cBodyHalfExtents(0.0362, 0.0236, 0.0362);
const btScalar CDynamics3DEPuckModel::m_fBodyMass(0.242);
const btTransform CDynamics3DEPuckModel::m_cBodyOffset(btQuaternion(0.0, 0.0, 0.0, 1.0), btVector3(0.0,0.00125,0.0));
const btTransform CDynamics3DEPuckModel::m_cBodyGeometricOffset(btQuaternion(0.0, 0.0, 0.0, 1.0), btVector3(0.0, -0.0236, 0.0));
const btVector3 CDynamics3DEPuckModel::m_cWheelHalfExtents(0.02125,0.0015,0.02125);
const btScalar CDynamics3DEPuckModel::m_fWheelMass(0.006);
const btTransform CDynamics3DEPuckModel::m_cWheelGeometricOffset(btQuaternion(0.0, 0.0, 0.0, 1.0), btVector3(0.0,-0.0015,0.0));
const btTransform CDynamics3DEPuckModel::m_cLeftWheelOffset(btQuaternion(btVector3(-1,0,0), SIMD_HALF_PI), btVector3(0.0, 0.02125, -0.0255));
const btTransform CDynamics3DEPuckModel::m_cRightWheelOffset(btQuaternion(btVector3(1,0,0), SIMD_HALF_PI), btVector3(0.0, 0.02125, 0.0255));
const btVector3 CDynamics3DEPuckModel::m_cBodyToRightWheelJointOffset(0.0, -0.0036, 0.0255);
const btVector3 CDynamics3DEPuckModel::m_cRightWheelToBodyJointOffset(0.0, 0.0015, 0.0);
const btQuaternion CDynamics3DEPuckModel::m_cBodyToRightWheelJointRotation(btVector3(-1,0,0), SIMD_HALF_PI);
const btVector3 CDynamics3DEPuckModel::m_cBodyToLeftWheelJointOffset(0.0, -0.0036, -0.0255);
const btVector3 CDynamics3DEPuckModel::m_cLeftWheelToBodyJointOffset(0.0, 0.0015, -0.0);
const btQuaternion CDynamics3DEPuckModel::m_cBodyToLeftWheelJointRotation(btVector3(1,0,0), SIMD_HALF_PI);
/* TODO calibrate these values */
const btScalar CDynamics3DEPuckModel::m_fWheelMotorMaxImpulse(0.15);
const btScalar CDynamics3DEPuckModel::m_fWheelFriction(5.0);

/****************************************/
/****************************************/

}
75 changes: 75 additions & 0 deletions src/plugins/robots/e-puck/simulator/dynamics3d_epuck_model.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,75 @@
/**
* @file <argos3/plugins/robots/e-puck/simulator/dynamics3d_epuck_model.h>
*
* @author Michael Allwright - <[email protected]>
*/

#ifndef DYNAMICS3D_EPUCK_MODEL_H
#define DYNAMICS3D_EPUCK_MODEL_H

namespace argos {
class CDynamics3DEPuckModel;
class CEPuckEntity;
class CWheeledEntity;
}

#include <argos3/plugins/simulator/physics_engines/dynamics3d/bullet/BulletDynamics/Featherstone/btMultiBodyJointMotor.h>
#include <argos3/plugins/simulator/physics_engines/dynamics3d/bullet/BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.h>
#include <argos3/plugins/simulator/physics_engines/dynamics3d/dynamics3d_multi_body_object_model.h>

namespace argos {

class CDynamics3DEPuckModel : public CDynamics3DMultiBodyObjectModel {

public:

CDynamics3DEPuckModel(CDynamics3DEngine& c_engine,
CEPuckEntity& c_epuck);

virtual ~CDynamics3DEPuckModel() {}

virtual void Reset();

virtual void CalculateBoundingBox();

virtual void UpdateEntityStatus();

virtual void UpdateFromEntityStatus();

virtual void AddToWorld(btMultiBodyDynamicsWorld& c_world);

virtual void RemoveFromWorld(btMultiBodyDynamicsWorld& c_world);

private:
/* joint constraints */
std::unique_ptr<btMultiBodyJointMotor> m_ptrLeftMotor;
std::unique_ptr<btMultiBodyJointMotor> m_ptrRightMotor;
/* links */
std::shared_ptr<CBase> m_ptrBody;
std::shared_ptr<CLink> m_ptrLeftWheel;
std::shared_ptr<CLink> m_ptrRightWheel;
/* entities */
CWheeledEntity& m_cWheeledEntity;
/* lower base data */
static const btVector3 m_cBodyHalfExtents;
static const btScalar m_fBodyMass;
static const btTransform m_cBodyOffset;
static const btTransform m_cBodyGeometricOffset;
/* wheel data */
static const btVector3 m_cWheelHalfExtents;
static const btScalar m_fWheelMass;
static const btTransform m_cWheelGeometricOffset;
static const btTransform m_cLeftWheelOffset;
static const btTransform m_cRightWheelOffset;
static const btVector3 m_cBodyToRightWheelJointOffset;
static const btVector3 m_cRightWheelToBodyJointOffset;
static const btQuaternion m_cBodyToRightWheelJointRotation;
static const btVector3 m_cBodyToLeftWheelJointOffset;
static const btVector3 m_cLeftWheelToBodyJointOffset;
static const btQuaternion m_cBodyToLeftWheelJointRotation;
static const btScalar m_fWheelMotorMaxImpulse;
static const btScalar m_fWheelFriction;
};
}

#endif
Original file line number Diff line number Diff line change
Expand Up @@ -37,25 +37,9 @@ namespace argos {
#ifdef ARGOS_WITH_LUA
void CCI_PositioningSensor::ReadingsToLuaState(lua_State* pt_lua_state) {
lua_getfield(pt_lua_state, -1, "positioning");
lua_getfield(pt_lua_state, -1, "position");
lua_pushnumber(pt_lua_state, m_sReading.Position.GetX());
lua_setfield(pt_lua_state, -2, "x");
lua_pushnumber(pt_lua_state, m_sReading.Position.GetY());
lua_setfield(pt_lua_state, -2, "y");
lua_pushnumber(pt_lua_state, m_sReading.Position.GetZ());
lua_setfield(pt_lua_state, -2, "z");
m_sReading.Orientation.ToAngleAxis(m_cAngle, m_cAxis);
lua_getfield (pt_lua_state, -2, "orientation");
lua_pushnumber(pt_lua_state, m_cAngle.GetValue());
lua_setfield (pt_lua_state, -2, "angle");
lua_getfield (pt_lua_state, -1, "axis");
lua_pushnumber(pt_lua_state, m_cAxis.GetX());
lua_setfield (pt_lua_state, -2, "x");
lua_pushnumber(pt_lua_state, m_cAxis.GetY());
lua_setfield (pt_lua_state, -2, "y");
lua_pushnumber(pt_lua_state, m_cAxis.GetZ());
lua_setfield (pt_lua_state, -2, "z");
lua_pop(pt_lua_state, 4);
CLuaUtility::AddToTable(pt_lua_state, "position", m_sReading.Position);
CLuaUtility::AddToTable(pt_lua_state, "orientation", m_sReading.Orientation);
lua_pop(pt_lua_state, 1);
}
#endif

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -265,7 +265,7 @@ namespace argos {

}
}
/* With this call to reset, the multi-body model is configured and ready to be added */
/* Finalize model with a reset */
Reset();
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,8 +59,8 @@ namespace argos {
m_ptrBody = std::make_shared<CBody>(*this, &sAnchor, ptrShape, sData);
/* Transfer the body to the base class */
m_vecBodies.push_back(m_ptrBody);
/* Synchronize with the entity in the space */
UpdateEntityStatus();
/* Finalize model with a reset */
Reset();
}

/****************************************/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,8 +59,8 @@ namespace argos {
m_ptrBody = std::make_shared<CBody>(*this, &sAnchor, ptrShape, sData);
/* Transfer the body to the base class */
m_vecBodies.push_back(m_ptrBody);
/* Synchronize with the entity in the space */
UpdateEntityStatus();
/* Finalize model with a reset */
Reset();
}

/****************************************/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -80,8 +80,9 @@ namespace argos {
++itPlugin) {
itPlugin->second->UnregisterModel(*itModel->second);
}
/* Reset the model */
/* Remove model from world */
itModel->second->RemoveFromWorld(m_cWorld);
/* Reset the model */
itModel->second->Reset();
}
/* Run the destructors on bullet's components */
Expand Down
Loading

0 comments on commit 0dae5fa

Please sign in to comment.