@@ -480,45 +480,41 @@ void GazeboSystem::registerGazeboTopics(
480480 int n_states = 0 ;
481481
482482 // STEP 1
483- for (unsigned int j = 0 ; j < hardware_info.joints .size (); j++)
484- {
485- auto &info = hardware_info.joints [j];
483+ for (unsigned int j = 0 ; j < hardware_info.joints .size (); j++) {
484+ auto & info = hardware_info.joints [j];
486485
487- for (unsigned int i = 0 ; i < info.command_interfaces .size (); i++)
488- {
486+ for (unsigned int i = 0 ; i < info.command_interfaces .size (); i++) {
489487 std::string if_name = info.command_interfaces [i].name ;
490488
491- if (if_name != " position" && if_name != " velocity" && if_name != " effort" )
492- {
489+ if (if_name != " position" && if_name != " velocity" && if_name != " effort" ) {
493490 ++n_commands;
494491 }
495492 }
496493
497- for (unsigned int i = 0 ; i < info.state_interfaces .size (); i++)
498- {
494+ for (unsigned int i = 0 ; i < info.state_interfaces .size (); i++) {
499495 std::string if_name = info.state_interfaces [i].name ;
500496
501- if (if_name != " position" && if_name != " velocity" && if_name != " effort" )
502- {
497+ if (if_name != " position" && if_name != " velocity" && if_name != " effort" ) {
503498 ++n_states;
504499 }
505500 }
506501 }
507502
508- for (unsigned int j = 0 ; j < hardware_info.sensors .size (); j++)
509- {
510- auto &info = hardware_info.sensors [j];
503+ for (unsigned int j = 0 ; j < hardware_info.sensors .size (); j++) {
504+ auto & info = hardware_info.sensors [j];
511505
512- for (unsigned int i = 0 ; i < info.state_interfaces .size (); i++)
513- {
506+ for (unsigned int i = 0 ; i < info.state_interfaces .size (); i++) {
514507 std::string if_name = info.state_interfaces [i].name ;
515508
516- if (if_name != " position" && if_name != " velocity" && if_name != " effort"
517- && if_name != " orientation.x" && if_name != " orientation.y" && if_name != " orientation.z"
518- && if_name != " orientation.w" && if_name != " angular_velocity.x" && if_name != " angular_velocity.y"
519- && if_name != " angular_velocity.z" && if_name != " linear_acceleration.x" && if_name != " linear_acceleration.y"
520- && if_name != " linear_acceleration.z" && if_name != " force.x" && if_name != " force.y" && if_name != " force.z"
521- && if_name != " torque.x" && if_name != " torque.y" && if_name != " torque.z" )
509+ if (if_name != " position" && if_name != " velocity" && if_name != " effort" &&
510+ if_name != " orientation.x" && if_name != " orientation.y" && if_name != " orientation.z" &&
511+ if_name != " orientation.w" && if_name != " angular_velocity.x" &&
512+ if_name != " angular_velocity.y" &&
513+ if_name != " angular_velocity.z" && if_name != " linear_acceleration.x" &&
514+ if_name != " linear_acceleration.y" &&
515+ if_name != " linear_acceleration.z" && if_name != " force.x" && if_name != " force.y" &&
516+ if_name != " force.z" &&
517+ if_name != " torque.x" && if_name != " torque.y" && if_name != " torque.z" )
522518 {
523519 ++n_states;
524520 }
@@ -533,31 +529,28 @@ void GazeboSystem::registerGazeboTopics(
533529 unsigned int cs = 0 ;
534530
535531 // STEP 2
536- for (unsigned int j = 0 ; j < hardware_info.joints .size (); j++)
537- {
538- auto &info = hardware_info.joints [j];
532+ for (unsigned int j = 0 ; j < hardware_info.joints .size (); j++) {
533+ auto & info = hardware_info.joints [j];
539534 std::string joint_name = this ->dataPtr ->joint_names_ [j] = info.name ;
540535
541- RCLCPP_INFO_STREAM (this ->nh_ ->get_logger (), " Registering gazebo topics for joint: " << joint_name);
536+ RCLCPP_INFO_STREAM (
537+ this ->nh_ ->get_logger (), " Registering gazebo topics for joint: " << joint_name);
542538
543539 RCLCPP_INFO_STREAM (this ->nh_ ->get_logger (), " \t Command:" );
544540
545- for (unsigned int i = 0 ; i < info.command_interfaces .size (); i++)
546- {
541+ for (unsigned int i = 0 ; i < info.command_interfaces .size (); i++) {
547542 std::string if_name = info.command_interfaces [i].name ;
548543 std::string initial_v = info.command_interfaces [i].initial_value ;
549544
550- if (if_name != " position" && if_name != " velocity" && if_name != " effort" )
551- {
545+ if (if_name != " position" && if_name != " velocity" && if_name != " effort" ) {
552546 RCLCPP_INFO_STREAM (this ->nh_ ->get_logger (), " \t\t " << if_name);
553547
554548 this ->dataPtr ->command_interfaces_ .emplace_back (
555- joint_name,
556- if_name,
557- &(this ->dataPtr ->gazebo_topic_cmd_ [cc]));
549+ joint_name,
550+ if_name,
551+ &(this ->dataPtr ->gazebo_topic_cmd_ [cc]));
558552
559- if (!initial_v.empty ())
560- {
553+ if (!initial_v.empty ()) {
561554 this ->dataPtr ->gazebo_topic_cmd_ [cc] = std::stod (initial_v);
562555 }
563556
@@ -575,17 +568,17 @@ void GazeboSystem::registerGazeboTopics(
575568 for (unsigned int i = 0 ; i < info.state_interfaces .size (); i++) {
576569 std::string if_name = info.state_interfaces [i].name ;
577570
578- if (if_name != " position" && if_name != " velocity" && if_name != " effort" ){
571+ if (if_name != " position" && if_name != " velocity" && if_name != " effort" ) {
579572 RCLCPP_INFO_STREAM (this ->nh_ ->get_logger (), " \t\t " << if_name);
580573
581574 this ->dataPtr ->state_interfaces_ .emplace_back (
582- joint_name,
583- if_name,
584- &(this ->dataPtr ->gazebo_topic_fbk_ [cs]));
585-
575+ joint_name,
576+ if_name,
577+ &(this ->dataPtr ->gazebo_topic_fbk_ [cs]));
578+
586579 dataPtr->gz_subs_ .push_back (
587580 this ->dataPtr ->transport_nh_ ->Subscribe <gazebo::msgs::Any>(
588- " ~/" + joint_name + " /" + if_name,
581+ " ~/" + joint_name + " /" + if_name,
589582 [this , cs](ConstAnyPtr & msg) mutable -> void {
590583 this ->dataPtr ->gazebo_topic_fbk_ [cs] = msg->double_value ();
591584 }
@@ -600,31 +593,34 @@ void GazeboSystem::registerGazeboTopics(
600593 auto & info = hardware_info.sensors [j];
601594 std::string sensor_name = info.name ;
602595
603- RCLCPP_INFO_STREAM (this ->nh_ ->get_logger (), " Registering gazebo topics for sensor: " << sensor_name);
596+ RCLCPP_INFO_STREAM (
597+ this ->nh_ ->get_logger (), " Registering gazebo topics for sensor: " << sensor_name);
604598
605599 RCLCPP_INFO_STREAM (this ->nh_ ->get_logger (), " \t State:" );
606600
607- for (unsigned int i = 0 ; i < info.state_interfaces .size (); i++)
608- {
601+ for (unsigned int i = 0 ; i < info.state_interfaces .size (); i++) {
609602 std::string if_name = info.state_interfaces [i].name ;
610603
611- if (if_name != " position" && if_name != " velocity" && if_name != " effort"
612- && if_name != " orientation.x" && if_name != " orientation.y" && if_name != " orientation.z"
613- && if_name != " orientation.w" && if_name != " angular_velocity.x" && if_name != " angular_velocity.y"
614- && if_name != " angular_velocity.z" && if_name != " linear_acceleration.x" && if_name != " linear_acceleration.y"
615- && if_name != " linear_acceleration.z" && if_name != " force.x" && if_name != " force.y" && if_name != " force.z"
616- && if_name != " torque.x" && if_name != " torque.y" && if_name != " torque.z" )
604+ if (if_name != " position" && if_name != " velocity" && if_name != " effort" &&
605+ if_name != " orientation.x" && if_name != " orientation.y" && if_name != " orientation.z" &&
606+ if_name != " orientation.w" && if_name != " angular_velocity.x" &&
607+ if_name != " angular_velocity.y" &&
608+ if_name != " angular_velocity.z" && if_name != " linear_acceleration.x" &&
609+ if_name != " linear_acceleration.y" &&
610+ if_name != " linear_acceleration.z" && if_name != " force.x" && if_name != " force.y" &&
611+ if_name != " force.z" &&
612+ if_name != " torque.x" && if_name != " torque.y" && if_name != " torque.z" )
617613 {
618614 RCLCPP_INFO_STREAM (this ->nh_ ->get_logger (), " \t\t " << if_name);
619615
620616 this ->dataPtr ->state_interfaces_ .emplace_back (
621- sensor_name,
622- if_name,
623- &(this ->dataPtr ->gazebo_topic_fbk_ [cs]));
624-
617+ sensor_name,
618+ if_name,
619+ &(this ->dataPtr ->gazebo_topic_fbk_ [cs]));
620+
625621 dataPtr->gz_subs_ .push_back (
626622 this ->dataPtr ->transport_nh_ ->Subscribe <gazebo::msgs::Any>(
627- " ~/" + sensor_name + " /" + if_name,
623+ " ~/" + sensor_name + " /" + if_name,
628624 [this , cs](ConstAnyPtr & msg) mutable -> void {
629625 this ->dataPtr ->gazebo_topic_fbk_ [cs] = msg->double_value ();
630626 }
0 commit comments