Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Get rid of "std::endl" #918

Merged
merged 3 commits into from
Dec 14, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions moveit_core/backtrace/include/moveit/backtrace/backtrace.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,17 +48,17 @@ void get_backtrace(std::ostream& out)
void* array[500];
size_t size = backtrace(array, 500);
char** strings = backtrace_symbols((void* const*)array, size);
out << "Backtrace:" << std::endl;
out << "Backtrace: \n";
for (size_t i = 0; i < size; ++i)
{
out << " " << strings[i] << std::endl;
out << " " << strings[i] << '\n';
}
free(strings);
}
#else
void get_backtrace(std::ostream& out)
{
out << "Unable to get backtrace with the used compiler." << std::endl;
out << "Unable to get backtrace with the used compiler.\n";
}
#endif
} // namespace moveit
4 changes: 2 additions & 2 deletions moveit_core/collision_detection/src/collision_matrix.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -400,7 +400,7 @@ void AllowedCollisionMatrix::print(std::ostream& out) const
ss << std::setw(number_digits) << i;
out << std::setw(3) << ss.str().c_str()[j];
}
out << std::endl;
out << '\n';
}

for (std::size_t i = 0; i < names.size(); ++i)
Expand All @@ -417,7 +417,7 @@ void AllowedCollisionMatrix::print(std::ostream& out) const
else
out << std::setw(3) << '-';
}
out << std::endl;
out << '\n';
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -242,7 +242,7 @@ class BodyDecomposition
const Eigen::Isometry3d& new_relative_cylinder_pose)
{
// std::cerr << "Replacing " << collision_spheres_.size() << " with " <<
// new_collision_spheres.size() << std::endl;
// new_collision_spheres.size() << '\n';
collision_spheres_ = new_collision_spheres;
relative_cylinder_pose_ = new_relative_cylinder_pose;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -504,7 +504,7 @@ bool CollisionEnvDistanceField::getIntraGroupCollisions(const collision_detectio
}
// std::cerr << "Bounding spheres for " << gsr->dfce_->link_names_[i] <<
// " and " << gsr->dfce_->link_names_[j]
// << " intersect" << std::endl;
// << " intersect" << '\n';
}
int num_pair = -1;
std::string name_1;
Expand Down Expand Up @@ -572,7 +572,7 @@ bool CollisionEnvDistanceField::getIntraGroupCollisions(const collision_detectio
double dist = gradient.norm();
// std::cerr << "Dist is " << dist << " rad " <<
// (*collision_spheres_1)[k].radius_+(*collision_spheres_2)[l].radius_
// << std::endl;
// << '\n';

if (dist < (*collision_spheres_1)[k].radius_ + (*collision_spheres_2)[l].radius_)
{
Expand Down Expand Up @@ -805,14 +805,14 @@ DistanceFieldCacheEntryPtr CollisionEnvDistanceField::generateDistanceFieldCache
// std::cerr << "Checking touch links for " << link_name << " and " <<
// attached_bodies[j]->getName()
// << " num " << attached_bodies[j]->getTouchLinks().size()
// << std::endl;
// << '\n';
// touch links take priority
if (link_attached_bodies[j]->getTouchLinks().find(link_name) != link_attached_bodies[j]->getTouchLinks().end())
{
dfce->intra_group_collision_enabled_[i][att_count + dfce->link_names_.size()] = false;
// std::cerr << "Setting intra group for " << link_name << " and
// attached body " << link_attached_bodies[j]->getName() << " to
// false" << std::endl;
// false" << '\n';
}
}
}
Expand Down Expand Up @@ -852,7 +852,7 @@ DistanceFieldCacheEntryPtr CollisionEnvDistanceField::generateDistanceFieldCache
// TODO - allow for touch links to be attached bodies?
// else {
// std::cerr << "Setting not allowed for " << link_name << " and " <<
// dfce->link_names_[j] << std::endl;
// dfce->link_names_[j] << '\n';
//}
}
}
Expand Down Expand Up @@ -1226,7 +1226,7 @@ void CollisionEnvDistanceField::getGroupStateRepresentation(const DistanceFieldC
// const moveit::core::LinkModel* ls =
// state.getLinkStateVector()[dfce->attached_body_link_state_indices_[i]];
/// std::cerr << "Attached " << dfce->attached_body_names_[i] << " index "
/// << dfce->attached_body_link_state_indices_[i] << std::endl;
/// << dfce->attached_body_link_state_indices_[i] << '\n';
gsr->attached_body_decompositions_.push_back(
getAttachedBodySphereDecomposition(state.getAttachedBody(dfce->attached_body_names_[i]), resolution_));
gsr->gradients_[i + dfce->link_names_.size()].types.resize(
Expand Down Expand Up @@ -1351,7 +1351,7 @@ bool CollisionEnvDistanceField::compareCacheEntryToAllowedCollisionMatrix(
// " << dfce->link_names_[j]
// << " went from " <<
// dfce->intra_group_collision_enabled_[i][j] << " to " <<
// intra_collision_enabled << std::endl;
// intra_collision_enabled << '\n';
return false;
}
}
Expand Down
68 changes: 34 additions & 34 deletions moveit_core/constraint_samplers/test/pr2_arm_ik.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -262,7 +262,7 @@ void PR2ArmIK::computeIKShoulderPan(const Eigen::Isometry3f& g_in, const double&
theta4[1] = -acos_angle;

#ifdef DEBUG
std::cout << "ComputeIK::theta3:" << numerator << "," << denominator << "," << std::endl << theta4[0] << std::endl;
std::cout << "ComputeIK::theta3:" << numerator << "," << denominator << ",\n" << theta4[0] << '\n';
#endif

for (double theta : theta4)
Expand All @@ -272,7 +272,7 @@ void PR2ArmIK::computeIKShoulderPan(const Eigen::Isometry3f& g_in, const double&
sint4 = sin(t4);

#ifdef DEBUG
std::cout << "t4 " << t4 << std::endl;
std::cout << "t4 " << t4 << '\n';
#endif
if (std::isnan(t4))
continue;
Expand All @@ -295,7 +295,7 @@ void PR2ArmIK::computeIKShoulderPan(const Eigen::Isometry3f& g_in, const double&
continue;

#ifdef DEBUG
std::cout << "t2 " << t2 << std::endl;
std::cout << "t2 " << t2 << '\n';
#endif
sint2 = sin(t2);
cost2 = cos(t2);
Expand All @@ -318,7 +318,7 @@ void PR2ArmIK::computeIKShoulderPan(const Eigen::Isometry3f& g_in, const double&
sint3 = sin(t3);
cost3 = cos(t3);
#ifdef DEBUG
std::cout << "t3 " << t3 << std::endl;
std::cout << "t3 " << t3 << '\n';
#endif
if (fabs((shoulder_upperarm_offset_ - shoulder_elbow_offset_ +
(shoulder_elbow_offset_ - shoulder_wrist_offset_) * cost4) *
Expand Down Expand Up @@ -395,14 +395,14 @@ void PR2ArmIK::computeIKShoulderPan(const Eigen::Isometry3f& g_in, const double&
continue;

#ifdef DEBUG
std::cout << "t6 " << t6 << std::endl;
std::cout << "t6 " << t6 << '\n';
#endif
if (fabs(cos(t6) - grhs_local(0, 0)) > IK_EPS)
continue;

if (fabs(sin(t6)) < IK_EPS)
{
// std::cout << "Singularity" << std::endl;
// std::cout << "Singularity" << '\n';
theta5[0] = acos(grhs_local(1, 1)) / 2.0;
theta7[0] = theta7[0];
theta7[1] = M_PI + theta7[0];
Expand All @@ -416,13 +416,13 @@ void PR2ArmIK::computeIKShoulderPan(const Eigen::Isometry3f& g_in, const double&
theta5[1] = M_PI + theta5[0];
}
#ifdef DEBUG
std::cout << "theta1: " << t1 << std::endl;
std::cout << "theta2: " << t2 << std::endl;
std::cout << "theta3: " << t3 << std::endl;
std::cout << "theta4: " << t4 << std::endl;
std::cout << "theta5: " << t5 << std::endl;
std::cout << "theta6: " << t6 << std::endl;
std::cout << "theta7: " << t7 << std::endl << std::endl << std::endl;
std::cout << "theta1: " << t1 << '\n';
std::cout << "theta2: " << t2 << '\n';
std::cout << "theta3: " << t3 << '\n';
std::cout << "theta4: " << t4 << '\n';
std::cout << "theta5: " << t5 << '\n';
std::cout << "theta6: " << t6 << '\n';
std::cout << "theta7: " << t7 << '\n' << '\n' << '\n';
#endif
for (int lll = 0; lll < 2; ++lll)
{
Expand All @@ -434,8 +434,8 @@ void PR2ArmIK::computeIKShoulderPan(const Eigen::Isometry3f& g_in, const double&
continue;

#ifdef DEBUG
std::cout << "t5" << t5 << std::endl;
std::cout << "t7" << t7 << std::endl;
std::cout << "t5" << t5 << '\n';
std::cout << "t7" << t7 << '\n';
#endif
if (fabs(sin(t6) * sin(t7) - grhs_local(0, 1)) > IK_EPS ||
fabs(cos(t7) * sin(t6) - grhs_local(0, 2)) > IK_EPS)
Expand All @@ -453,8 +453,8 @@ void PR2ArmIK::computeIKShoulderPan(const Eigen::Isometry3f& g_in, const double&
#ifdef DEBUG
std::cout << "SOLN " << solution_ik[0] << " " << solution_ik[1] << " " << solution_ik[2] << " "
<< solution_ik[3] << " " << solution_ik[4] << " " << solution_ik[5] << " " << solution_ik[6]
<< std::endl
<< std::endl;
<< '\n'
<< '\n';
#endif
}
}
Expand Down Expand Up @@ -542,7 +542,7 @@ void PR2ArmIK::computeIKShoulderRoll(const Eigen::Isometry3f& g_in, const double
cost4 = cos(t4);
sint4 = sin(t4);
#ifdef DEBUG
std::cout << "t4 " << t4 << std::endl;
std::cout << "t4 " << t4 << '\n';
#endif
if (std::isnan(t4))
continue;
Expand All @@ -558,7 +558,7 @@ void PR2ArmIK::computeIKShoulderRoll(const Eigen::Isometry3f& g_in, const double
{
t2 = theta;
#ifdef DEBUG
std::cout << "t2 " << t2 << std::endl;
std::cout << "t2 " << t2 << '\n';
#endif
if (!checkJointLimits(t2, 1))
{
Expand All @@ -574,7 +574,7 @@ void PR2ArmIK::computeIKShoulderRoll(const Eigen::Isometry3f& g_in, const double
if (!solveCosineEqn(at, bt, ct, theta1[0], theta1[1]))
{
#ifdef DEBUG
std::cout << "could not solve cosine equation for t1" << std::endl;
std::cout << "could not solve cosine equation for t1" << '\n';
#endif
continue;
}
Expand All @@ -583,7 +583,7 @@ void PR2ArmIK::computeIKShoulderRoll(const Eigen::Isometry3f& g_in, const double
{
t1 = theta;
#ifdef DEBUG
std::cout << "t1 " << t1 << std::endl;
std::cout << "t1 " << t1 << '\n';
#endif
if (!checkJointLimits(t1, 0))
{
Expand Down Expand Up @@ -690,7 +690,7 @@ void PR2ArmIK::computeIKShoulderRoll(const Eigen::Isometry3f& g_in, const double
{
t6 = theta6[mm];
#ifdef DEBUG
std::cout << "t6 " << t6 << std::endl;
std::cout << "t6 " << t6 << '\n';
#endif
if (!checkJointLimits(t6, 5))
{
Expand All @@ -702,7 +702,7 @@ void PR2ArmIK::computeIKShoulderRoll(const Eigen::Isometry3f& g_in, const double

if (fabs(sin(t6)) < IK_EPS)
{
// std::cout << "Singularity" << std::endl;
// std::cout << "Singularity" << '\n';
theta5[0] = acos(grhs_local(1, 1)) / 2.0;
theta7[0] = theta5[0];
// theta7[1] = M_PI+theta7[0];
Expand Down Expand Up @@ -730,20 +730,20 @@ void PR2ArmIK::computeIKShoulderRoll(const Eigen::Isometry3f& g_in, const double
}

#ifdef DEBUG
std::cout << "t5 " << t5 << std::endl;
std::cout << "t7 " << t7 << std::endl;
std::cout << "t5 " << t5 << '\n';
std::cout << "t7 " << t7 << '\n';
#endif
// if(fabs(sin(t6)*sin(t7)-grhs_local(0,1)) > IK_EPS || fabs(cos(t7)*sin(t6)-grhs_local(0,2)) > IK_EPS)
// continue;

#ifdef DEBUG
std::cout << "theta1: " << t1 << std::endl;
std::cout << "theta2: " << t2 << std::endl;
std::cout << "theta3: " << t3 << std::endl;
std::cout << "theta4: " << t4 << std::endl;
std::cout << "theta5: " << t5 << std::endl;
std::cout << "theta6: " << t6 << std::endl;
std::cout << "theta7: " << t7 << std::endl << std::endl << std::endl;
std::cout << "theta1: " << t1 << '\n';
std::cout << "theta2: " << t2 << '\n';
std::cout << "theta3: " << t3 << '\n';
std::cout << "theta4: " << t4 << '\n';
std::cout << "theta5: " << t5 << '\n';
std::cout << "theta6: " << t6 << '\n';
std::cout << "theta7: " << t7 << '\n' << '\n' << '\n';
#endif

solution_ik[0] = normalize_angle(t1 * angle_multipliers_[0]);
Expand All @@ -757,8 +757,8 @@ void PR2ArmIK::computeIKShoulderRoll(const Eigen::Isometry3f& g_in, const double
#ifdef DEBUG
std::cout << "SOLN " << solution_ik[0] << " " << solution_ik[1] << " " << solution_ik[2] << " "
<< solution_ik[3] << " " << solution_ik[4] << " " << solution_ik[5] << " " << solution_ik[6]
<< std::endl
<< std::endl;
<< '\n'
<< '\n';
#endif
}
}
Expand Down
4 changes: 2 additions & 2 deletions moveit_core/constraint_samplers/test/pr2_arm_ik.h
Original file line number Diff line number Diff line change
Expand Up @@ -96,15 +96,15 @@ inline bool solveCosineEqn(const double& a, const double& b, const double& c, do
if (fabs(denom) < IK_EPS) // should never happen, wouldn't make sense but make sure it is checked nonetheless
{
#ifdef DEBUG
std::cout << "denom: " << denom << std::endl;
std::cout << "denom: " << denom << '\n';
#endif
return false;
}
double rhs_ratio = c / denom;
if (rhs_ratio < -1 || rhs_ratio > 1)
{
#ifdef DEBUG
std::cout << "rhs_ratio: " << rhs_ratio << std::endl;
std::cout << "rhs_ratio: " << rhs_ratio << '\n';
#endif
return false;
}
Expand Down
24 changes: 12 additions & 12 deletions moveit_core/distance_field/src/propagation_distance_field.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -477,11 +477,11 @@ void PropagationDistanceField::propagateNegative()
if (new_distance_sq > max_distance_sq_)
continue;
// std::cout << "Looking at " << nloc.x() << " " << nloc.y() << " " << nloc.z() << " " << new_distance_sq << " "
// << neighbor->negative_distance_square_ << std::endl;
// << neighbor->negative_distance_square_ << '\n';
if (new_distance_sq < neighbor->negative_distance_square_)
{
// std::cout << "Updating " << nloc.x() << " " << nloc.y() << " " << nloc.z() << " " << new_distance_sq <<
// std::endl;
// '\n';
// update the neighboring voxel
neighbor->negative_distance_square_ = new_distance_sq;
neighbor->closest_negative_point_ = vptr->closest_negative_point_;
Expand Down Expand Up @@ -627,13 +627,13 @@ bool PropagationDistanceField::worldToGrid(double world_x, double world_y, doubl

bool PropagationDistanceField::writeToStream(std::ostream& os) const
{
os << "resolution: " << resolution_ << std::endl;
os << "size_x: " << size_x_ << std::endl;
os << "size_y: " << size_y_ << std::endl;
os << "size_z: " << size_z_ << std::endl;
os << "origin_x: " << origin_x_ << std::endl;
os << "origin_y: " << origin_y_ << std::endl;
os << "origin_z: " << origin_z_ << std::endl;
os << "resolution: " << resolution_ << '\n';
os << "size_x: " << size_x_ << '\n';
os << "size_y: " << size_y_ << '\n';
os << "size_z: " << size_z_ << '\n';
os << "origin_x: " << origin_x_ << '\n';
os << "origin_y: " << origin_y_ << '\n';
os << "origin_z: " << origin_z_ << '\n';
// now the binary stuff

// first writing to zlib compressed buffer
Expand All @@ -653,7 +653,7 @@ bool PropagationDistanceField::writeToStream(std::ostream& os) const
{
if (getCell(x, y, z + zi).distance_square_ == 0)
{
// std::cout << "Marking obs cell " << x << " " << y << " " << z+zi << std::endl;
// std::cout << "Marking obs cell " << x << " " << y << " " << z+zi << '\n';
bs[zi] = 1;
}
}
Expand Down Expand Up @@ -720,7 +720,7 @@ bool PropagationDistanceField::readFromStream(std::istream& is)
in.push(boost::iostreams::zlib_decompressor());
in.push(is);

// std::cout << "Nums " << getXNumCells() << " " << getYNumCells() << " " << getZNumCells() << std::endl;
// std::cout << "Nums " << getXNumCells() << " " << getYNumCells() << " " << getZNumCells() << '\n';

EigenSTL::vector_Vector3i obs_points;
for (unsigned int x = 0; x < static_cast<unsigned int>(getXNumCells()); ++x)
Expand All @@ -741,7 +741,7 @@ bool PropagationDistanceField::readFromStream(std::istream& is)
{
if (inbit[zi] == 1)
{
// std::cout << "Adding obs cell " << x << " " << y << " " << z+zi << std::endl;
// std::cout << "Adding obs cell " << x << " " << y << " " << z+zi << '\n';
obs_points.push_back(Eigen::Vector3i(x, y, z + zi));
}
}
Expand Down
Loading