Prasad, It looks like you're using your own custom action type called "eskorta_move::move_baseAction" to communicate with the navigation stack that expects an action of type "move_base_msgs::MoveBaseAction" and, therefore, the md5sums are not matching up. Why are you trying to use your own action type? Does the code work if you switch to using the action in move_base_msgs instead? Hope this helps, Eitan On Sun, Oct 24, 2010 at 11:21 PM, Prasad Dixit wrote: > > Hello, > > I am running a navigation stack and sending goal through coding like below: > > using namespace eskorta_move; > > typedef actionlib::SimpleActionClient > Client; > > // Called once when the goal completes > void doneCb(const actionlib::SimpleClientGoalState& state, > const move_baseResultConstPtr& result) > { > ROS_INFO("Finished in state [%s]", state.toString().c_str()); > ROS_INFO("[X]:%f [Y]:%f [W]: %f",result->base_position.pose.position.x, > result->base_position.pose.position.y, > result->base_position.pose.orientation.w); > ros::shutdown(); > } > > // Called once when the goal becomes active > void activeCb() > { > ROS_INFO("Goal just went active"); > } > > // Called every time feedback is received for the goal > void feedbackCb(const move_baseFeedbackConstPtr& feedback) > { > ROS_INFO("[X]:%f [Y]:%f [W]: %f",feedback->base_position.pose.position.x, > feedback->base_position.pose.position.y, > feedback->base_position.pose.orientation.w); > } > > > > int main(int argc, char** argv) > { > ros::init(argc, argv, "move_eskorta"); > > Client client("eskorta_base", true); > //client.waitForServer(); > > while(!client.waitForServer(ros::Duration(5.0))){ > ROS_INFO("Waiting for the move_base action server to come up"); > } > > > eskorta_move::move_baseGoal goal; > > // [ INFO] [1287828403.230367166]: Setting goal: Frame:/map, > Position(-0.423, 1.915, 0.000), Orientation(0.000, 0.000, 0.000, 1.000) = > Angle: 0.000 > goal.target_pose.header.frame_id = "map"; > goal.target_pose.header.stamp = ros::Time::now(); > > // 1 mtr forward, -2.0 mtr left and 1.0 orientation > goal.target_pose.pose.position.x = -0.423; > goal.target_pose.pose.position.y = 1.915; > goal.target_pose.pose.orientation.w = 1.000; > goal.vicinity_range = 0.0; > > ROS_INFO("Sending goal"); > client.sendGoal(goal, &doneCb, &activeCb, &feedbackCb); > client.waitForResult(); > > > /* if(client.getState() == actionlib::SimpleClientGoalState::SUCCEEDED){ > > ROS_INFO("Hooray, the base moved meter forward, %s"); > } > else{ > // client.getResult(); > ROS_INFO("The base failed to move forward 1 meter for some reason, %s" > );}*/ > > ros::spin(); > > return 0; > } > > After running stack, in between i send executable of this code. So as, > robot > will receive a goal. > > After that, i get non-stop messages like below, > [ INFO] [1287986999.289579675]: Waiting for the move_base action server to > come up > > Map is already received by the Navigation stack. > > When i try to change the code, > Client client("eskorta_base", true); to Client client("move_base", true); > then i get an error: > > [ERROR] [1287987393.000424927]: Client [/move_eskorta] wants topic > /move_base/result to have datatype/md5sum > [eskorta_move/move_baseActionResult/0ab416b06f38c51e47c9638aa34125b5], but > our version has > [move_base_msgs/MoveBaseActionResult/1eb06eeff08fa7ea874431638cb52332]. > Dropping connection. > > where, move_base another node running through Navigation stack. > > Am i missing something? > > Thanks in advance. > - Prasad > > > > -- > View this message in context: > http://ros-users.122217.n3.nabble.com/Actionlib-Server-communication-tp1765659p1765659.html > Sent from the ROS-Users mailing list archive at Nabble.com. > _______________________________________________ > ros-users mailing list > ros-users@code.ros.org > https://code.ros.org/mailman/listinfo/ros-users >