Skip to content

Commit

Permalink
found a bunch more places which needed aligned allocation. but someho…
Browse files Browse the repository at this point in the history
…w I'm still getting the alignment debug crash on RigidBody (from the RBM constructor) on win32
  • Loading branch information
RussTedrake committed Oct 11, 2015
1 parent 08eef3c commit e1865db
Show file tree
Hide file tree
Showing 5 changed files with 9 additions and 9 deletions.
2 changes: 1 addition & 1 deletion drake/examples/Pendulum/runDynamics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ int main(int argc, char* argv[]) {
if(!lcm->good())
return 1;

DrakeSystemPtr p = make_shared<PendulumWithBotVis>(lcm);
DrakeSystemPtr p = allocate_shared<PendulumWithBotVis>(Eigen::AlignedAllocator<PendulumWithBotVis>(),lcm);
runLCM(p,*lcm,0,50,p->getRandomState());

cout << "output frame: " << p->getOutputFrame() << endl;
Expand Down
2 changes: 1 addition & 1 deletion drake/examples/Pendulum/runLQR.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ int main(int argc, char* argv[]) {
if(!lcm->good())
return 1;

std::shared_ptr<PendulumWithBotVis> pendulum = make_shared<PendulumWithBotVis>(lcm);
std::shared_ptr<PendulumWithBotVis> pendulum = allocate_shared<PendulumWithBotVis>(Eigen::AlignedAllocator<PendulumWithBotVis>(),lcm);
DrakeSystemPtr controller = pendulum->balanceLQR();

DrakeSystemPtr sys = feedback(pendulum,controller);
Expand Down
4 changes: 2 additions & 2 deletions drake/systems/plants/RigidBodyManipulator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ RigidBodyManipulator::RigidBodyManipulator(const std::string &urdf_filename, con
{
a_grav << 0, 0, 0, 0, 0, -9.81;

shared_ptr<RigidBody> b = make_shared<RigidBody>();
shared_ptr<RigidBody> b = allocate_shared<RigidBody>(Eigen::aligned_allocator<RigidBody>());
b->linkname = "world";
b->robotnum = 0;
b->body_index = 0;
Expand All @@ -60,7 +60,7 @@ RigidBodyManipulator::RigidBodyManipulator(void) :
{
a_grav << 0, 0, 0, 0, 0, -9.81;

shared_ptr<RigidBody> b = make_shared<RigidBody>();
shared_ptr<RigidBody> b = allocate_shared<RigidBody>(Eigen::aligned_allocator<RigidBody>());
b->linkname = "world";
b->robotnum = 0;
b->body_index = 0;
Expand Down
6 changes: 3 additions & 3 deletions drake/systems/plants/RigidBodyManipulatorURDF.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -713,7 +713,7 @@ bool parseLoop(RigidBodyManipulator* model, TiXmlElement* node)
cerr << "ERROR parsing loop joint rpy" << endl;
return false;
}
std::shared_ptr<RigidBodyFrame> frameA = make_shared<RigidBodyFrame>(name+"FrameA",body,xyz,rpy);
std::shared_ptr<RigidBodyFrame> frameA = allocate_shared<RigidBodyFrame>(Eigen::aligned_allocator<RigidBodyFrame>(), name+"FrameA",body,xyz,rpy);

link_node = node->FirstChildElement("link2");
linkname = link_node->Attribute("link");
Expand All @@ -732,7 +732,7 @@ bool parseLoop(RigidBodyManipulator* model, TiXmlElement* node)
cerr << "ERROR parsing loop joint rpy" << endl;
return false;
}
std::shared_ptr<RigidBodyFrame> frameB = make_shared<RigidBodyFrame>(name+"FrameB",body,xyz,rpy);
std::shared_ptr<RigidBodyFrame> frameB = allocate_shared<RigidBodyFrame>(Eigen::aligned_allocator<RigidBodyFrame>(), name+"FrameB",body,xyz,rpy);

TiXmlElement* axis_node = node->FirstChildElement("axis");
if (axis_node && !parseVectorAttribute(axis_node, "xyz", axis)) {
Expand Down Expand Up @@ -778,7 +778,7 @@ bool parseFrame(RigidBodyManipulator* model, TiXmlElement* node)
Matrix4d T;
T << rpy2rotmat(rpy), xyz, 0,0,0,1;

std::shared_ptr<RigidBodyFrame> frame = make_shared<RigidBodyFrame>(frame_name,body,T);
std::shared_ptr<RigidBodyFrame> frame = allocate_shared<RigidBodyFrame>(Eigen::aligned_allocator<RigidBodyFrame>(), frame_name,body,T);
model->addFrame(frame);


Expand Down
4 changes: 2 additions & 2 deletions drake/systems/plants/constructModelmex.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ void mexFunction( int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[] )
//DEBUG
//mexPrintf("constructModelmex: body %d\n",i);
//END_DEBUG
shared_ptr<RigidBody> b = make_shared<RigidBody>();
shared_ptr<RigidBody> b = allocate_shared<RigidBody>(Eigen::aligned_allocator<RigidBody>());
b->body_index = i;

b->linkname = mxGetStdString(mxGetPropertySafe(pBodies, i, "linkname"));
Expand Down Expand Up @@ -352,7 +352,7 @@ void mexFunction( int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[] )
//mexPrintf("constructModelmex: Parsing frames\n");
//END_DEBUG
for (int i = 0; i < num_frames; i++) {
shared_ptr<RigidBodyFrame> fr = make_shared<RigidBodyFrame>();
shared_ptr<RigidBodyFrame> fr = allocate_shared<RigidBodyFrame>(Eigen::aligned_allocator<RigidBodyFrame>());

fr->name = mxGetStdString(mxGetPropertySafe(pFrames, i, "name"));

Expand Down

0 comments on commit e1865db

Please sign in to comment.