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 types in range loops to avoid copy due to different type #143

Merged
merged 2 commits into from
Jul 15, 2020
Merged
Changes from 1 commit
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
10 changes: 5 additions & 5 deletions src/robot_state_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -175,14 +175,14 @@ void RobotStatePublisher::setupURDF(const std::string & urdf_xml)

// Initialize the mimic map
mimic_.clear();
for (const std::pair<std::string, urdf::JointSharedPtr> & i : model_->joints_) {
for (const auto & i : model_->joints_) {
if (i.second->mimic) {
mimic_.insert(std::make_pair(i.first, i.second->mimic));
}
}

KDL::SegmentMap segments_map = tree.getSegments();
for (const std::pair<std::string, KDL::TreeElement> & segment : segments_map) {
for (const auto & segment : segments_map) {
RCLCPP_INFO(get_logger(), "got segment %s", segment.first.c_str());
}

Expand Down Expand Up @@ -239,7 +239,7 @@ void RobotStatePublisher::publishTransforms(
std::vector<geometry_msgs::msg::TransformStamped> tf_transforms;

// loop over all joints
for (const std::pair<std::string, double> & jnt : joint_positions) {
for (const auto & jnt : joint_positions) {
std::map<std::string, SegmentPair>::iterator seg = segments_.find(jnt.first);
if (seg != segments_.end()) {
geometry_msgs::msg::TransformStamped tf_transform =
Expand All @@ -260,7 +260,7 @@ void RobotStatePublisher::publishFixedTransforms()
std::vector<geometry_msgs::msg::TransformStamped> tf_transforms;

// loop over all fixed segments
for (const std::pair<std::string, SegmentPair> & seg : segments_fixed_) {
for (const auto & seg : segments_fixed_) {
geometry_msgs::msg::TransformStamped tf_transform = kdlToTransform(seg.second.segment.pose(0));
rclcpp::Time now = this->now();
if (!use_tf_static_) {
Expand Down Expand Up @@ -321,7 +321,7 @@ void RobotStatePublisher::callbackJointState(const sensor_msgs::msg::JointState:
joint_positions.insert(std::make_pair(state->name[i], state->position[i]));
}

for (const std::pair<std::string, urdf::JointMimicSharedPtr> & i : mimic_) {
for (const auto & i : mimic_) {
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;
Expand Down