Skip to content
Snippets Groups Projects
Commit c167be57 authored by Farid Alijani's avatar Farid Alijani
Browse files

controller dock

parent 13237428
Branches
No related tags found
No related merge requests found
...@@ -73,7 +73,7 @@ double ImageConverter::i_term = 0; ...@@ -73,7 +73,7 @@ double ImageConverter::i_term = 0;
double ImageConverter::d_term = 0; double ImageConverter::d_term = 0;
double ImageConverter::control_signal; double ImageConverter::control_signal;
double ImageConverter::prop_gain = 15; double ImageConverter::prop_gain = 5;
double ImageConverter::integ_gain = 3; double ImageConverter::integ_gain = 3;
double ImageConverter::deriv_gain = 0; double ImageConverter::deriv_gain = 0;
......
...@@ -340,7 +340,7 @@ void ImageConverter::ProgStart(int argc,char** argv) ...@@ -340,7 +340,7 @@ void ImageConverter::ProgStart(int argc,char** argv)
tf::Vector3(x_t, y_t, z_t)), tf::Vector3(x_t, y_t, z_t)),
(ros::Time::now()/* - ros::Duration(35)*/), (ros::Time::now()/* - ros::Duration(35)*/),
"/camera", "/camera",
"marker")); "/marker"));
// Now publish the pose message, remember the offsets // Now publish the pose message, remember the offsets
msg.header.frame_id = "/camera"; msg.header.frame_id = "/camera";
......
No preview for this file type
No preview for this file type
...@@ -33,7 +33,7 @@ RobotDocking::RobotDocking() : ac("Robot_move", true) ...@@ -33,7 +33,7 @@ RobotDocking::RobotDocking() : ac("Robot_move", true)
commandPub = node.advertise<geometry_msgs::Twist>("/base_controller/command",1); 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() ...@@ -45,7 +45,7 @@ void RobotDocking::ProgStart()
while (ros::ok() && keepMoving) while (ros::ok() && keepMoving)
{ {
//dock(FORWARD_SPEED_MPS); dock(FORWARD_SPEED_MPS);
ros::spinOnce(); ros::spinOnce();
rate.sleep(); rate.sleep();
} }
...@@ -89,8 +89,8 @@ void RobotDocking::Controller(double Reference, double RobPose, double dt) ...@@ -89,8 +89,8 @@ void RobotDocking::Controller(double Reference, double RobPose, double dt)
void RobotDocking::dock(double speed) void RobotDocking::dock(double speed)
{ {
geometry_msgs::Twist msg; geometry_msgs::Twist msg;
//msg.linear.x = speed; msg.linear.x = speed;
msg.angular.z = speed; //msg.angular.z = speed;
commandPub.publish(msg); commandPub.publish(msg);
ROS_INFO_STREAM(" Current speed of robot: " << speed << " m/s \n"); ROS_INFO_STREAM(" Current speed of robot: " << speed << " m/s \n");
......
...@@ -33,7 +33,7 @@ RobotDocking::RobotDocking() : ac("Robot_move", true) ...@@ -33,7 +33,7 @@ RobotDocking::RobotDocking() : ac("Robot_move", true)
commandPub = node.advertise<geometry_msgs::Twist>("/base_controller/command",1); 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) ...@@ -89,8 +89,8 @@ void RobotDocking::Controller(double Reference, double RobPose, double dt)
void RobotDocking::dock(double speed) void RobotDocking::dock(double speed)
{ {
geometry_msgs::Twist msg; geometry_msgs::Twist msg;
//msg.linear.x = speed; msg.linear.x = speed;
msg.angular.z = speed; //msg.angular.z = speed;
commandPub.publish(msg); commandPub.publish(msg);
ROS_INFO_STREAM(" Current speed of robot: " << speed << " m/s \n"); ROS_INFO_STREAM(" Current speed of robot: " << speed << " m/s \n");
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment