Renamed error_message and warning_message macros.

error_message and warning_message are common strings that are likely to
collide. Renamed to bt_id_{error,warning}_message to more strongly
uniquify.

grep -r error_message -l src/BulletInverseDynamics | \
  xargs sed -i -e "s/error_message/bt_id_error_message/g"

grep -r warning_message -l src/BulletInverseDynamics | \
  xargs sed -i -e "s/warning_message/bt_id_warning_message/g"
This commit is contained in:
Michael Beardsworth
2018-07-24 11:19:42 -07:00
parent 0e1dce41ea
commit 3f03b41091
17 changed files with 124 additions and 124 deletions

View File

@@ -6,7 +6,7 @@ namespace btInverseDynamics {
#define CHECK_NULLPTR() \
do { \
if (m_reference == 0x0) { \
error_message("m_reference == 0x0\n"); \
bt_id_error_message("m_reference == 0x0\n"); \
return -1; \
} \
} while (0)
@@ -14,7 +14,7 @@ namespace btInverseDynamics {
#define TRY(x) \
do { \
if (x == -1) { \
error_message("error calling " #x "\n"); \
bt_id_error_message("error calling " #x "\n"); \
return -1; \
} \
} while (0)

View File

@@ -48,7 +48,7 @@ int CoilCreator::getBody(int body_index, int* parent_index, JointType* joint_typ
vec3* body_axis_of_motion, idScalar* mass, vec3* body_r_body_com,
mat33* body_I_body, int* user_int, void** user_ptr) const {
if (body_index < 0 || body_index >= m_num_bodies) {
error_message("invalid body index %d\n", body_index);
bt_id_error_message("invalid body index %d\n", body_index);
return -1;
}
*parent_index = m_parent[body_index];

View File

@@ -32,7 +32,7 @@ DillCreator::DillCreator(int level)
const idScalar alpha_DH = 0.0;
if (-1 == recurseDill(m_level, parent, d_DH, a_DH, alpha_DH)) {
error_message("recurseDill failed\n");
bt_id_error_message("recurseDill failed\n");
abort();
}
}
@@ -49,7 +49,7 @@ int DillCreator::getBody(const int body_index, int* parent_index, JointType* joi
vec3* body_axis_of_motion, idScalar* mass, vec3* body_r_body_com,
mat33* body_I_body, int* user_int, void** user_ptr) const {
if (body_index < 0 || body_index >= m_num_bodies) {
error_message("invalid body index %d\n", body_index);
bt_id_error_message("invalid body index %d\n", body_index);
return -1;
}
*parent_index = m_parent[body_index];
@@ -69,12 +69,12 @@ int DillCreator::getBody(const int body_index, int* parent_index, JointType* joi
int DillCreator::recurseDill(const int level, const int parent, const idScalar d_DH_in,
const idScalar a_DH_in, const idScalar alpha_DH_in) {
if (level < 0) {
error_message("invalid level parameter (%d)\n", level);
bt_id_error_message("invalid level parameter (%d)\n", level);
return -1;
}
if (m_current_body >= m_num_bodies || m_current_body < 0) {
error_message("invalid body parameter (%d, num_bodies: %d)\n", m_current_body,
bt_id_error_message("invalid body parameter (%d, num_bodies: %d)\n", m_current_body,
m_num_bodies);
return -1;
}

View File

@@ -6,11 +6,11 @@ MultiBodyNameMap::MultiBodyNameMap() {}
int MultiBodyNameMap::addBody(const int index, const std::string& name) {
if (m_index_to_body_name.count(index) > 0) {
error_message("trying to add index %d again\n", index);
bt_id_error_message("trying to add index %d again\n", index);
return -1;
}
if (m_body_name_to_index.count(name) > 0) {
error_message("trying to add name %s again\n", name.c_str());
bt_id_error_message("trying to add name %s again\n", name.c_str());
return -1;
}
@@ -22,11 +22,11 @@ int MultiBodyNameMap::addBody(const int index, const std::string& name) {
int MultiBodyNameMap::addJoint(const int index, const std::string& name) {
if (m_index_to_joint_name.count(index) > 0) {
error_message("trying to add index %d again\n", index);
bt_id_error_message("trying to add index %d again\n", index);
return -1;
}
if (m_joint_name_to_index.count(name) > 0) {
error_message("trying to add name %s again\n", name.c_str());
bt_id_error_message("trying to add name %s again\n", name.c_str());
return -1;
}
@@ -39,7 +39,7 @@ int MultiBodyNameMap::addJoint(const int index, const std::string& name) {
int MultiBodyNameMap::getBodyName(const int index, std::string* name) const {
std::map<int, std::string>::const_iterator it = m_index_to_body_name.find(index);
if (it == m_index_to_body_name.end()) {
error_message("index %d not known\n", index);
bt_id_error_message("index %d not known\n", index);
return -1;
}
*name = it->second;
@@ -49,7 +49,7 @@ int MultiBodyNameMap::getBodyName(const int index, std::string* name) const {
int MultiBodyNameMap::getJointName(const int index, std::string* name) const {
std::map<int, std::string>::const_iterator it = m_index_to_joint_name.find(index);
if (it == m_index_to_joint_name.end()) {
error_message("index %d not known\n", index);
bt_id_error_message("index %d not known\n", index);
return -1;
}
*name = it->second;
@@ -59,7 +59,7 @@ int MultiBodyNameMap::getJointName(const int index, std::string* name) const {
int MultiBodyNameMap::getBodyIndex(const std::string& name, int* index) const {
std::map<std::string, int>::const_iterator it = m_body_name_to_index.find(name);
if (it == m_body_name_to_index.end()) {
error_message("name %s not known\n", name.c_str());
bt_id_error_message("name %s not known\n", name.c_str());
return -1;
}
*index = it->second;
@@ -69,7 +69,7 @@ int MultiBodyNameMap::getBodyIndex(const std::string& name, int* index) const {
int MultiBodyNameMap::getJointIndex(const std::string& name, int* index) const {
std::map<std::string, int>::const_iterator it = m_joint_name_to_index.find(name);
if (it == m_joint_name_to_index.end()) {
error_message("name %s not known\n", name.c_str());
bt_id_error_message("name %s not known\n", name.c_str());
return -1;
}
*index = it->second;

View File

@@ -17,7 +17,7 @@ MultiBodyTree* CreateMultiBodyTree(const MultiBodyTreeCreator& creator) {
MultiBodyTree* tree = new MultiBodyTree();
if (0x0 == tree) {
error_message("cannot allocate tree\n");
bt_id_error_message("cannot allocate tree\n");
return 0x0;
}
@@ -26,7 +26,7 @@ MultiBodyTree* CreateMultiBodyTree(const MultiBodyTreeCreator& creator) {
// get number of bodies in the system
if (-1 == creator.getNumBodies(&num_bodies)) {
error_message("getting body indices\n");
bt_id_error_message("getting body indices\n");
delete tree;
return 0x0;
}
@@ -38,7 +38,7 @@ MultiBodyTree* CreateMultiBodyTree(const MultiBodyTreeCreator& creator) {
creator.getBody(index, &parent_index, &joint_type, &body_r_parent_body_ref,
&body_R_parent_ref, &body_axis_of_motion, &mass, &body_r_body_com,
&body_I_body, &user_int, &user_ptr)) {
error_message("getting data for body %d\n", index);
bt_id_error_message("getting data for body %d\n", index);
delete tree;
return 0x0;
}
@@ -47,14 +47,14 @@ MultiBodyTree* CreateMultiBodyTree(const MultiBodyTreeCreator& creator) {
tree->addBody(index, parent_index, joint_type, body_r_parent_body_ref,
body_R_parent_ref, body_axis_of_motion, mass, body_r_body_com,
body_I_body, user_int, user_ptr)) {
error_message("adding body %d\n", index);
bt_id_error_message("adding body %d\n", index);
delete tree;
return 0x0;
}
}
// finalize initialization
if (-1 == tree->finalize()) {
error_message("building system\n");
bt_id_error_message("building system\n");
delete tree;
return 0x0;
}

View File

@@ -7,17 +7,17 @@ namespace btInverseDynamics {
int writeGraphvizDotFile(const MultiBodyTree* tree, const MultiBodyNameMap* map,
const char* filename) {
if (0x0 == tree) {
error_message("tree pointer is null\n");
bt_id_error_message("tree pointer is null\n");
return -1;
}
if (0x0 == filename) {
error_message("filename is null\n");
bt_id_error_message("filename is null\n");
return -1;
}
FILE* fp = fopen(filename, "w");
if (NULL == fp) {
error_message("cannot open file %s for writing\n", filename);
bt_id_error_message("cannot open file %s for writing\n", filename);
return -1;
}
fprintf(fp, "// to generate postscript file, run dot -Tps %s -o %s.ps\n"
@@ -29,7 +29,7 @@ int writeGraphvizDotFile(const MultiBodyTree* tree, const MultiBodyNameMap* map,
std::string name;
if (0x0 != map) {
if (-1 == map->getBodyName(body, &name)) {
error_message("can't get name of body %d\n", body);
bt_id_error_message("can't get name of body %d\n", body);
return -1;
}
fprintf(fp, " %d [label=\"%d/%s\"];\n", body, body, name.c_str());
@@ -40,15 +40,15 @@ int writeGraphvizDotFile(const MultiBodyTree* tree, const MultiBodyNameMap* map,
const char* joint_type;
int qi;
if (-1 == tree->getParentIndex(body, &parent)) {
error_message("indexing error\n");
bt_id_error_message("indexing error\n");
return -1;
}
if (-1 == tree->getJointTypeStr(body, &joint_type)) {
error_message("indexing error\n");
bt_id_error_message("indexing error\n");
return -1;
}
if (-1 == tree->getDoFOffset(body, &qi)) {
error_message("indexing error\n");
bt_id_error_message("indexing error\n");
return -1;
}
if (-1 != parent) {

View File

@@ -47,7 +47,7 @@ int RandomTreeCreator::getBody(const int body_index, int* parent_index, JointTyp
*joint_type = FLOATING;
break;
default:
error_message("randomInt() result out of range\n");
bt_id_error_message("randomInt() result out of range\n");
return -1;
}

View File

@@ -35,7 +35,7 @@ int User2InternalIndex::buildMapping() {
user_root_index = current_root_index;
} else {
if (user_root_index != current_root_index) {
error_message("multiple roots (at least) %d and %d\n", user_root_index,
bt_id_error_message("multiple roots (at least) %d and %d\n", user_root_index,
current_root_index);
return -1;
}
@@ -75,7 +75,7 @@ int User2InternalIndex::user2internal(const int user, int *internal) const {
*internal = it->second;
return 0;
} else {
error_message("no user index %d\n", user);
bt_id_error_message("no user index %d\n", user);
return -1;
}
}
@@ -92,7 +92,7 @@ int User2InternalIndex::internal2user(const int internal, int *user) const {
*user = it->second;
return 0;
} else {
error_message("no internal index %d\n", internal);
bt_id_error_message("no internal index %d\n", internal);
return -1;
}
}

View File

@@ -6,7 +6,7 @@ btMultiBodyTreeCreator::btMultiBodyTreeCreator() : m_initialized(false) {}
int btMultiBodyTreeCreator::createFromBtMultiBody(const btMultiBody *btmb, const bool verbose) {
if (0x0 == btmb) {
error_message("cannot create MultiBodyTree from null pointer\n");
bt_id_error_message("cannot create MultiBodyTree from null pointer\n");
return -1;
}
@@ -184,10 +184,10 @@ int btMultiBodyTreeCreator::createFromBtMultiBody(const btMultiBody *btmb, const
link.parent_r_parent_body_ref(2) = bt_link.m_eVector[2];
break;
case btMultibodyLink::eSpherical:
error_message("spherical joints not implemented\n");
bt_id_error_message("spherical joints not implemented\n");
return -1;
case btMultibodyLink::ePlanar:
error_message("planar joints not implemented\n");
bt_id_error_message("planar joints not implemented\n");
return -1;
case btMultibodyLink::eFixed:
link.joint_type = FIXED;
@@ -203,7 +203,7 @@ int btMultiBodyTreeCreator::createFromBtMultiBody(const btMultiBody *btmb, const
link.parent_r_parent_body_ref(2) = bt_link.m_eVector[2];
break;
default:
error_message("unknown btMultiBody::eFeatherstoneJointType %d\n",
bt_id_error_message("unknown btMultiBody::eFeatherstoneJointType %d\n",
bt_link.m_jointType);
return -1;
}
@@ -231,7 +231,7 @@ int btMultiBodyTreeCreator::createFromBtMultiBody(const btMultiBody *btmb, const
int btMultiBodyTreeCreator::getNumBodies(int *num_bodies) const {
if (false == m_initialized) {
error_message("btMultiBody not converted yet\n");
bt_id_error_message("btMultiBody not converted yet\n");
return -1;
}
@@ -245,12 +245,12 @@ int btMultiBodyTreeCreator::getBody(const int body_index, int *parent_index, Joi
vec3 *body_r_body_com, mat33 *body_I_body, int *user_int,
void **user_ptr) const {
if (false == m_initialized) {
error_message("MultiBodyTree not created yet\n");
bt_id_error_message("MultiBodyTree not created yet\n");
return -1;
}
if (body_index < 0 || body_index >= static_cast<int>(m_data.size())) {
error_message("index out of range (got %d but only %zu bodies)\n", body_index,
bt_id_error_message("index out of range (got %d but only %zu bodies)\n", body_index,
m_data.size());
return -1;
}

View File

@@ -12,11 +12,11 @@ namespace btInverseDynamics {
int compareInverseAndForwardDynamics(vecx &q, vecx &u, vecx &dot_u, btVector3 &gravity, bool verbose,
btMultiBody *btmb, MultiBodyTree *id_tree, double *pos_error,
double *acc_error) {
// call function and return -1 if it does, printing an error_message
// call function and return -1 if it does, printing an bt_id_error_message
#define RETURN_ON_FAILURE(x) \
do { \
if (-1 == x) { \
error_message("calling " #x "\n"); \
bt_id_error_message("calling " #x "\n"); \
return -1; \
} \
} while (0)
@@ -75,13 +75,13 @@ int compareInverseAndForwardDynamics(vecx &q, vecx &u, vecx &dot_u, btVector3 &g
}
// sanity check
if (q_index != q.size()) {
error_message("error in number of dofs for btMultibody and MultiBodyTree\n");
bt_id_error_message("error in number of dofs for btMultibody and MultiBodyTree\n");
return -1;
}
// run inverse dynamics to determine joint_forces for given q, u, dot_u
if (-1 == id_tree->calculateInverseDynamics(q, u, dot_u, &joint_forces)) {
error_message("calculating inverse dynamics\n");
bt_id_error_message("calculating inverse dynamics\n");
return -1;
}
@@ -143,7 +143,7 @@ int compareInverseAndForwardDynamics(vecx &q, vecx &u, vecx &dot_u, btVector3 &g
// sanity check
if (q_index != q.size()) {
error_message("error in number of dofs for btMultibody and MultiBodyTree\n");
bt_id_error_message("error in number of dofs for btMultibody and MultiBodyTree\n");
return -1;
}
@@ -223,12 +223,12 @@ int compareInverseAndForwardDynamics(vecx &q, vecx &u, vecx &dot_u, btVector3 &g
{
mat33 world_T_body;
if (-1 == id_tree->getBodyTransform(0, &world_T_body)) {
error_message("getting transform for body %d\n", 0);
bt_id_error_message("getting transform for body %d\n", 0);
return -1;
}
vec3 world_com;
if (-1 == id_tree->getBodyCoM(0, &world_com)) {
error_message("getting com for body %d\n", 0);
bt_id_error_message("getting com for body %d\n", 0);
return -1;
}
if (verbose) {
@@ -261,11 +261,11 @@ int compareInverseAndForwardDynamics(vecx &q, vecx &u, vecx &dot_u, btVector3 &g
vec3 id_world_com;
if (-1 == id_tree->getBodyTransform(l + 1, &id_world_T_body)) {
error_message("getting transform for body %d\n", l);
bt_id_error_message("getting transform for body %d\n", l);
return -1;
}
if (-1 == id_tree->getBodyCoM(l + 1, &id_world_com)) {
error_message("getting com for body %d\n", l);
bt_id_error_message("getting com for body %d\n", l);
return -1;
}
if (verbose) {