Skip to content

Commit

Permalink
remove status_message
Browse files Browse the repository at this point in the history
  • Loading branch information
chapulina committed Nov 21, 2018
1 parent f470d2a commit 6387f4a
Show file tree
Hide file tree
Showing 4 changed files with 11 additions and 15 deletions.
1 change: 0 additions & 1 deletion gazebo_msgs/srv/GetEntityState.srv
Original file line number Diff line number Diff line change
Expand Up @@ -9,4 +9,3 @@ std_msgs/Header header # Standard metadata for higher-level stampe
# * header.frame_id Filled with the relative_frame.
gazebo_msgs/EntityState state # Contains pose and twist.
bool success # Return true if get was successful. If false, the state contains garbage.
string status_message # Comments if available.
1 change: 0 additions & 1 deletion gazebo_msgs/srv/SetEntityState.srv
Original file line number Diff line number Diff line change
Expand Up @@ -2,4 +2,3 @@ gazebo_msgs/EntityState state # Entity state to set to.
# Be sure to fill all fields, values of zero have meaning.
---
bool success # Return true if setting state was successful.
string status_message # Comments if available.
2 changes: 1 addition & 1 deletion gazebo_plugins/worlds/gazebo_ros_diff_drive_demo.world
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
Try listening to TF:
ros2 run tf2_ros tf2_echo odom chassis
ros2 run tf2_ros tf2_echo odom_demo chassis
ros2 run tf2_ros tf2_echo chassis right_wheel
Expand Down
22 changes: 10 additions & 12 deletions gazebo_ros/src/gazebo_ros_state.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,9 +95,9 @@ void GazeboRosStatePrivate::GetEntityState(
auto entity = world_->EntityByName(_req->name);
if (!entity) {
_res->success = false;
_res->status_message = "GetEntityState: entity [" + _req->name + "] does not exist";

RCLCPP_ERROR(ros_node_->get_logger(), _res->status_message.c_str());
RCLCPP_ERROR(ros_node_->get_logger(),
"GetEntityState: entity [%s] does not exist", _req->name);
return;
}

Expand All @@ -122,10 +122,10 @@ void GazeboRosStatePrivate::GetEntityState(
"GetEntityState: reference_frame is empty/world, using inertial frame");
} else {
_res->success = false;
_res->status_message = "GetEntityState: reference entity [" + _req->name +
"] not found, did you forget to scope the entity's name?";

RCLCPP_ERROR(ros_node_->get_logger(), _res->status_message.c_str());
RCLCPP_ERROR(ros_node_->get_logger(),
"GetEntityState: reference entity [%s] not found, did you forget to scope the entity name?",
_req->name);
return;
}

Expand All @@ -140,7 +140,6 @@ void GazeboRosStatePrivate::GetEntityState(
_res->state.twist.angular = Convert<geometry_msgs::msg::Vector3>(entity_ang_vel);

_res->success = true;
_res->status_message = "GetEntityState: got entity state";
}

void GazeboRosStatePrivate::SetEntityState(
Expand All @@ -161,9 +160,9 @@ void GazeboRosStatePrivate::SetEntityState(
auto entity = world_->EntityByName(_req->state.name);
if (!entity) {
_res->success = false;
_res->status_message = "SetEntityState: entity [" + _req->state.name + "] does not exist";

RCLCPP_ERROR(ros_node_->get_logger(), _res->status_message.c_str());
RCLCPP_ERROR(ros_node_->get_logger(),
"SetEntityState: entity [%s] does not exist", _req->state.name);
return;
}

Expand All @@ -182,10 +181,10 @@ void GazeboRosStatePrivate::SetEntityState(
"SetEntityState: reference_frame is empty/world, using inertial frame");
} else {
_res->success = false;
_res->status_message = "GetEntityState: reference entity [" + _req->state.name +
"] not found, did you forget to scope the entity's name?";

RCLCPP_ERROR(ros_node_->get_logger(), _res->status_message.c_str());
RCLCPP_ERROR(ros_node_->get_logger(),
"GetEntityState: reference entity [%s] not found, did you forget to scope the entity name?",
_req->state.name);
return;
}

Expand All @@ -210,7 +209,6 @@ void GazeboRosStatePrivate::SetEntityState(

// Fill response
_res->success = true;
_res->status_message = "SetEntityState: set entity state done";
}

GZ_REGISTER_WORLD_PLUGIN(GazeboRosState)
Expand Down

0 comments on commit 6387f4a

Please sign in to comment.