vijay comments on api review

This commit is contained in:
meeussen 2009-09-23 23:48:19 +00:00
parent a173462840
commit 45a08f37e3
5 changed files with 9 additions and 10 deletions

View File

@ -24,7 +24,7 @@ set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
rosbuild_add_library(${PROJECT_NAME} src/joint_state_listener.cpp src/robot_state_publisher.cpp src/treefksolverposfull_recursive.cpp) rosbuild_add_library(${PROJECT_NAME} src/joint_state_listener.cpp src/robot_state_publisher.cpp src/treefksolverposfull_recursive.cpp)
rosbuild_add_executable(state_publisher src/state_publisher.cpp ) rosbuild_add_executable(state_publisher src/robot_state_publisher_node.cpp )
target_link_libraries(state_publisher ${PROJECT_NAME}) target_link_libraries(state_publisher ${PROJECT_NAME})
rosbuild_add_executable(test_publisher test/test_publisher.cpp ) rosbuild_add_executable(test_publisher test/test_publisher.cpp )

View File

@ -3,8 +3,9 @@
@htmlinclude manifest.html @htmlinclude manifest.html
This package contains the robot state publisher, which can be used as a library or as a ROS node. This package contains the robot state publisher, which can be used as
\li LIbrary use: robot_state_publisher::RobotStatePublisher a library or as a ROS node. The API documentation for the library can
\li Node use: robot_state_publisher::JointStateListener be found here: robot_state_publisher::RobotStatePublisher
**/ **/

View File

@ -59,6 +59,7 @@ public:
/** Publish transforms to tf /** Publish transforms to tf
* \param joint_positions A map of joint names and joint positions. * \param joint_positions A map of joint names and joint positions.
* \param time The time at which the joint positions were recorded * \param time The time at which the joint positions were recorded
* returns true on success; return false when the joint positions don't match the kinematic robot model
*/ */
bool publishTransforms(const std::map<std::string, double>& joint_positions, const ros::Time& time); bool publishTransforms(const std::map<std::string, double>& joint_positions, const ros::Time& time);

View File

@ -54,9 +54,7 @@ JointStateListener::JointStateListener(const KDL::Tree& tree)
publish_rate_ = Rate(publish_freq); publish_rate_ = Rate(publish_freq);
// subscribe to mechanism state // subscribe to mechanism state
string joint_state_topic; joint_state_sub_ = n_.subscribe("/joint_states", 1, &JointStateListener::callbackJointState, this);;
n_.param("joint_state_topic", joint_state_topic, string("/joint_states"));
joint_state_sub_ = n_.subscribe(joint_state_topic, 1, &JointStateListener::callbackJointState, this);;
}; };

View File

@ -57,9 +57,8 @@ int main(int argc, char** argv)
NodeHandle node; NodeHandle node;
// gets the location of the robot description on the parameter server // gets the location of the robot description on the parameter server
string param_name, full_param_name; string full_param_name;
node.param("~/robot_desc_param", param_name, string("robot_description")); node.searchParam("robot_description",full_param_name);
node.searchParam(param_name,full_param_name);
string robot_desc; string robot_desc;
// constructs a kdl tree from the robot model // constructs a kdl tree from the robot model