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

fix problems reported by CLion linter #146

Open
wants to merge 1 commit into
base: noetic-devel
Choose a base branch
from

Conversation

machinekoder
Copy link

The linter of CLion IDE reported a couple of problems and optimizations in the code.

Most noteworthy is the time_now change, since the ROS_WARN_THROTTLE call overwrites the local now variable.

@machinekoder machinekoder changed the title fix problems reported by linter fix problems reported by CLion linter Sep 2, 2020
@machinekoder machinekoder force-pushed the noetic-devel branch 2 times, most recently from 9605a2c to 1dab0db Compare September 2, 2020 16:04
@@ -65,15 +65,15 @@ class JointStateListener {
*/
JointStateListener(const KDL::Tree& tree, const MimicMap& m, const urdf::Model& model = urdf::Model());

JointStateListener(const std::shared_ptr<RobotStatePublisher>& rsp, const MimicMap& m);
JointStateListener(std::shared_ptr<RobotStatePublisher> rsp, MimicMap m);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I agree with the change to the rsp shared_ptr, but not with the change to the MimicMap. That will cause a copy of the map to be made, which isn't what we want.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Take a look at the mimic_ member variable. We initialize using move semantics now.

Comment on lines +75 to +76
void callbackJointState(const JointStateConstPtr& state);
void callbackFixedJoint(const ros::TimerEvent& e);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I believe that these are meant to be virtual, so that derivative classes can properly override them.

@@ -71,20 +72,20 @@ class RobotStatePublisher
/** Constructor
* \param tree The kinematic model of a robot, represented by a KDL Tree
*/
RobotStatePublisher(const KDL::Tree& tree, const urdf::Model& model = urdf::Model());
explicit RobotStatePublisher(const KDL::Tree& tree, urdf::Model model = urdf::Model());
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't think changing the constref to an object is what we want; that will cause the copy constructor to be called.

Comment on lines +84 to +88
void publishFixedTransforms(bool use_tf_static = false);
void publishTransforms(const std::map<std::string, double>& joint_positions, const ros::Time& time);

protected:
virtual void addChildren(const KDL::SegmentMap::const_iterator segment);
void addChildren(KDL::SegmentMap::const_iterator segment);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think all of these are meant to be virtual so this can be subclassed.

for (size_t i = 0; i < state->name.size(); ++i) {
ros::Time t = last_publish_time_[state->name[i]];
ros::Time last_published = time_now;
for (const auto & i : state->name) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Let's not use auto; it's hard to tell what the type is supposed to be then. I guess this would be const std::string & name then.

if(joint_positions.find(i->second->joint_name) != joint_positions.end()) {
double pos = joint_positions[i->second->joint_name] * i->second->multiplier + i->second->offset;
joint_positions.insert(make_pair(i->first, pos));
for (auto & i : mimic_) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We can change this to use the new loop style, but again, let's not make it auto. Also, we should have a more descriptive name for the variable than i. Finally, can the loop iteration variable be const here?

for (size_t i = 0; i < children.size(); ++i) {
const KDL::Segment& child = GetTreeElementSegment(children[i]->second);
SegmentPair s(GetTreeElementSegment(children[i]->second), root, child.getName());
for (auto i : children) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Again, no auto, can this be constref, and can we give this a better name?

@@ -98,17 +98,17 @@ void RobotStatePublisher::publishTransforms(const std::map<std::string, double>&
std::vector<geometry_msgs::TransformStamped> tf_transforms;

// loop over all joints
for (std::map<std::string, double>::const_iterator jnt = joint_positions.begin(); jnt != joint_positions.end(); jnt++) {
std::map<std::string, SegmentPair>::const_iterator seg = segments_.find(jnt->first);
for (auto & jnt : joint_positions) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

No auto, and can this be constref?


// loop over all fixed segments
for (std::map<std::string, SegmentPair>::const_iterator seg = segments_fixed_.begin(); seg != segments_fixed_.end(); seg++) {
geometry_msgs::TransformStamped tf_transform = tf2::kdlToTransform(seg->second.segment.pose(0));
for (const auto & seg : segments_fixed_) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

No auto.

for (std::map< std::string, urdf::JointSharedPtr >::iterator i = model.joints_.begin(); i != model.joints_.end(); i++) {
if (i->second->mimic) {
mimic.insert(std::make_pair(i->first, i->second->mimic));
for (auto & joint : model.joints_) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

No auto, and can this be constref?

@ahcorde ahcorde added the ros1 label Aug 21, 2024
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants