-
Notifications
You must be signed in to change notification settings - Fork 168
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
added repitition to robot_description reading #53
Closed
VahidAminZ
wants to merge
1
commit into
ros:kinetic-devel
from
shadow-robot:F#52_double_check_for_robot_description
Closed
Changes from all commits
Commits
File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -46,6 +46,8 @@ using namespace std; | |
using namespace ros; | ||
using namespace KDL; | ||
using namespace robot_state_publisher; | ||
const int JointStateListener::default_description_read_repetitions_ = 0; | ||
const double JointStateListener::default_description_read_delay_ = 0.5; | ||
|
||
JointStateListener::JointStateListener(const KDL::Tree& tree, const MimicMap& m, const urdf::Model& model) | ||
: state_publisher_(tree, model), mimic_(m) | ||
|
@@ -161,6 +163,36 @@ int main(int argc, char** argv) | |
ROS_WARN("The 'state_publisher' executable is deprecated. Please use 'robot_state_publisher' instead"); | ||
///////////////////////////////////////// end deprecation warning | ||
|
||
// Checks if the robot_description is present on the parameter server | ||
// If not, it will repeat the check for description_read_repetitions times with | ||
// description_read_delay seconds delay between the checks (both are read from parameter server). | ||
int description_read_repetitions; | ||
node.param("description_read_repetitions", description_read_repetitions, | ||
JointStateListener::default_description_read_repetitions_); | ||
if (description_read_repetitions < 0) { | ||
ROS_WARN_STREAM("Parameter description_read_repetitions is smaller than 0. Default value of " << | ||
JointStateListener::default_description_read_repetitions_ << " will be used."); | ||
description_read_repetitions = JointStateListener::default_description_read_repetitions_; | ||
} | ||
double description_read_delay; | ||
node.param("description_read_delay", description_read_delay, JointStateListener::default_description_read_delay_); | ||
if (description_read_delay <= 0) { | ||
ROS_WARN_STREAM("Parameter description_read_delay is smaller than or equal 0. Default value of " << | ||
JointStateListener::default_description_read_delay_ << " seconds will be used."); | ||
description_read_delay = JointStateListener::default_description_read_delay_; | ||
} | ||
for (size_t i = 0; i < description_read_repetitions; ++i) { | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Please add a test for this code. |
||
if (!node.hasParam("robot_description")) { | ||
ROS_WARN_STREAM("No robot_description parameter in namespace " << node.getNamespace() << | ||
". Will try " << description_read_repetitions - i << " more times with " << | ||
description_read_delay << " second(s) delay between repetitions."); | ||
ros::Duration(description_read_delay).sleep(); | ||
} | ||
else { | ||
break; | ||
} | ||
} | ||
|
||
// gets the location of the robot description on the parameter server | ||
urdf::Model model; | ||
if (!model.initParam("robot_description")) | ||
|
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I think adding these two constants to the JointStateListener class breaks ABI, which would block merging into kinetic-devel. Since these are only used in main(), how about they be local variables there?