Skip to content

Commit

Permalink
add "/" to the topic name in truck_pugin.cpp in roder to publish with…
Browse files Browse the repository at this point in the history
…out prefix
  • Loading branch information
tongtybj committed Jun 10, 2016
1 parent 145ad55 commit 9c97906
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 7 deletions.
2 changes: 0 additions & 2 deletions jsk_mbzirc_common/launch/mbzirc_arena_1.launch
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@
<arg name="headless" default="$(arg headless)"/>
</include>


<param name="truck/robot_description" command="$(find xacro)/xacro '$(find jsk_mbzirc_common)/urdf/truck.urdf.xacro'" />

<group ns="truck/ground_truth">
Expand All @@ -31,7 +30,6 @@
<param name="tf_prefix" type="string" value="truck/ground_truth" />
<param name="publish_frequency" type="double" value="50.0" />
</node>

</group>

</launch>
4 changes: 2 additions & 2 deletions jsk_mbzirc_common/src/mbzirc_gazebo_truck_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,8 +86,8 @@ void GazeboTruck::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
}

node_handle_ = new ros::NodeHandle(namespace_);
pub_score_ = node_handle_->advertise<std_msgs::String>("score", 1, true); // set latch true
pub_time_ = node_handle_->advertise<std_msgs::String>("remaining_time", 1);
pub_score_ = node_handle_->advertise<std_msgs::String>("/score", 1, true); // set latch true
pub_time_ = node_handle_->advertise<std_msgs::String>("/remaining_time", 1);

update_connection_ = event::Events::ConnectWorldUpdateBegin(boost::bind(&GazeboTruck::Update, this));
}
Expand Down
6 changes: 3 additions & 3 deletions jsk_mbzirc_tasks/config/task1.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -145,12 +145,12 @@ Visualization Manager:
Topic: /remaining_time_overlay
Value: true
font: DejaVu Sans Mono
height: 100
height: 50
left: 10
line width: 2
text size: 64
text size: 32
top: 10
width: 370
width: 500
Enabled: true
Global Options:
Background Color: 48; 48; 48
Expand Down

0 comments on commit 9c97906

Please sign in to comment.