diff --git a/MobileRobot/AugReaMarker/CamMark/camtomar/src/VisionControl.cpp b/MobileRobot/AugReaMarker/CamMark/camtomar/src/VisionControl.cpp index 47de5d7146659798a1b6f7bff084fccdb6a090fb..31ca1847bb69f18f260f6400e2378abd6d06529a 100644 --- a/MobileRobot/AugReaMarker/CamMark/camtomar/src/VisionControl.cpp +++ b/MobileRobot/AugReaMarker/CamMark/camtomar/src/VisionControl.cpp @@ -73,7 +73,7 @@ double ImageConverter::i_term = 0; double ImageConverter::d_term = 0; double ImageConverter::control_signal; -double ImageConverter::prop_gain = 15; +double ImageConverter::prop_gain = 5; double ImageConverter::integ_gain = 3; double ImageConverter::deriv_gain = 0; diff --git a/MobileRobot/AugReaMarker/CamMark/camtomar/src/VisionControl.cpp~ b/MobileRobot/AugReaMarker/CamMark/camtomar/src/VisionControl.cpp~ index 3f9b1e78ec910fd83b8a041e694e3e20bada12fe..47de5d7146659798a1b6f7bff084fccdb6a090fb 100644 --- a/MobileRobot/AugReaMarker/CamMark/camtomar/src/VisionControl.cpp~ +++ b/MobileRobot/AugReaMarker/CamMark/camtomar/src/VisionControl.cpp~ @@ -340,7 +340,7 @@ void ImageConverter::ProgStart(int argc,char** argv) tf::Vector3(x_t, y_t, z_t)), (ros::Time::now()/* - ros::Duration(35)*/), "/camera", - "marker")); + "/marker")); // Now publish the pose message, remember the offsets msg.header.frame_id = "/camera"; diff --git a/MobileRobot/Controller/PID/build/dock/CMakeFiles/dock.dir/src/dock.cpp.o b/MobileRobot/Controller/PID/build/dock/CMakeFiles/dock.dir/src/dock.cpp.o index 31ac88b67f528d495e42b531e574dc483d2d90e9..00a461ea1e92ab72127c7cafbb9f2fd7e06b9dde 100644 Binary files a/MobileRobot/Controller/PID/build/dock/CMakeFiles/dock.dir/src/dock.cpp.o and b/MobileRobot/Controller/PID/build/dock/CMakeFiles/dock.dir/src/dock.cpp.o differ diff --git a/MobileRobot/Controller/PID/devel/lib/dock/dock b/MobileRobot/Controller/PID/devel/lib/dock/dock index 10e309c19704a2c2f8da5500623f67c287702575..19e590c92ab00f26d0a46a9f264bfb3e84adf0e1 100755 Binary files a/MobileRobot/Controller/PID/devel/lib/dock/dock and b/MobileRobot/Controller/PID/devel/lib/dock/dock differ diff --git a/MobileRobot/Controller/PID/dock/src/dock.cpp b/MobileRobot/Controller/PID/dock/src/dock.cpp index 0f13003ee24701b7e86e24735e7e63ce382613cd..5743eb43e77a6168a17121cdba1a38610c562f20 100644 --- a/MobileRobot/Controller/PID/dock/src/dock.cpp +++ b/MobileRobot/Controller/PID/dock/src/dock.cpp @@ -33,7 +33,7 @@ RobotDocking::RobotDocking() : ac("Robot_move", true) commandPub = node.advertise<geometry_msgs::Twist>("/base_controller/command",1); - PosSub = node.subscribe("/visualize_pose_ekf",1,&RobotDocking::RobCurrPose,this); + //PosSub = node.subscribe("/visualize_pose_ekf",1,&RobotDocking::RobCurrPose,this); } @@ -45,7 +45,7 @@ void RobotDocking::ProgStart() while (ros::ok() && keepMoving) { - //dock(FORWARD_SPEED_MPS); + dock(FORWARD_SPEED_MPS); ros::spinOnce(); rate.sleep(); } @@ -89,8 +89,8 @@ void RobotDocking::Controller(double Reference, double RobPose, double dt) void RobotDocking::dock(double speed) { geometry_msgs::Twist msg; - //msg.linear.x = speed; - msg.angular.z = speed; + msg.linear.x = speed; + //msg.angular.z = speed; commandPub.publish(msg); ROS_INFO_STREAM(" Current speed of robot: " << speed << " m/s \n"); diff --git a/MobileRobot/Controller/PID/dock/src/dock.cpp~ b/MobileRobot/Controller/PID/dock/src/dock.cpp~ index 0f13003ee24701b7e86e24735e7e63ce382613cd..2b5513180acd64439ee7f1975d84180942d16948 100644 --- a/MobileRobot/Controller/PID/dock/src/dock.cpp~ +++ b/MobileRobot/Controller/PID/dock/src/dock.cpp~ @@ -33,7 +33,7 @@ RobotDocking::RobotDocking() : ac("Robot_move", true) commandPub = node.advertise<geometry_msgs::Twist>("/base_controller/command",1); - PosSub = node.subscribe("/visualize_pose_ekf",1,&RobotDocking::RobCurrPose,this); + //PosSub = node.subscribe("/visualize_pose_ekf",1,&RobotDocking::RobCurrPose,this); } @@ -89,8 +89,8 @@ void RobotDocking::Controller(double Reference, double RobPose, double dt) void RobotDocking::dock(double speed) { geometry_msgs::Twist msg; - //msg.linear.x = speed; - msg.angular.z = speed; + msg.linear.x = speed; + //msg.angular.z = speed; commandPub.publish(msg); ROS_INFO_STREAM(" Current speed of robot: " << speed << " m/s \n");