Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
26 changes: 22 additions & 4 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,22 @@
# ros_essentials_cpp
This repository contains the code needed for the Udemy course entitled
ROS For Beginners: Basics, Motion and OpenCV
https://www.udemy.com/ros-essentials/
# ROS For Beginners: Basics, Motion, and OpenCV - Udemy Course (ROS Noetic Version)

This repository contains the source code and materials for the Udemy course **ROS For Beginners: Basics, Motion, and OpenCV**. Learn the fundamentals of the Robot Operating System (ROS) and gain practical experience in robot motion and perception using OpenCV.

[![Course](https://img.shields.io/badge/Udemy-Course-blue)](https://www.udemy.com/ros-essentials/)
[![Discount](https://img.shields.io/badge/Discount-Coupons-green)](https://www.riotu-lab.org/udemy.php)

## Package: Assignment

- **topic01_basics**: ROS Basics and Foundation - Learn essential ROS concepts, such as topics, services, messages, and nodes.
- **topic02_motion**: Motion in ROS - Apply the concepts from the basics section to control robot motion and develop various trajectories using a cleaning robot simulation.
- **topic03_perception**: Perception in ROS - Discover how a robot perceives its environment using a camera, and how images are collected in ROS and processed in OpenCV.
- **topic04_perception02_laser**: Arduino Integration - Learn how to use Arduino boards and sensors with ROS using the ROSSERIAL Arduino interface, enabling integration with various Arduino sensors and boards.

### ROS Noetic and OpenCV4

This repository is updated for ROS Noetic, which uses OpenCV4. There are some differences between OpenCV4 and the previous versions (OpenCV3) used in ROS Melodic and Kinetic. The code in this repository has been updated to compile seamlessly on a fresh installation of ROS Noetic.

## Enroll in the Course

To enroll in the Udemy course, visit [ROS For Beginners: Basics, Motion and OpenCV](https://www.udemy.com/ros-essentials/).
For discount coupons, check [https://www.riotu-lab.org/udemy.php](https://www.riotu-lab.org/udemy.php).
1 change: 1 addition & 0 deletions include/readme
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
Noetic version
12 changes: 6 additions & 6 deletions src/topic01_basics/service/add_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,19 +12,19 @@ def add_two_ints_client(x, y):
add_two_ints = rospy.ServiceProxy('add_two_ints', AddTwoInts)
resp1 = add_two_ints(x, y)
return resp1.sum
except rospy.ServiceException, e:
print "Service call failed: %s"%e
except rospy.ServiceException(e):
print ("Service call failed: %s"%e)

def usage():
return "%s [x y]"%sys.argv[0]
return

if __name__ == "__main__":
if len(sys.argv) == 3:
x = int(sys.argv[1])
y = int(sys.argv[2])
else:
print usage()
print ("%s [x y]"%sys.argv[0])
sys.exit(1)
print "Requesting %s+%s"%(x, y)
print ("Requesting %s+%s"%(x, y))
s = add_two_ints_client(x, y)
print "%s + %s = %s"%(x, y, s)
print ("%s + %s = %s"%(x, y, s))
6 changes: 3 additions & 3 deletions src/topic01_basics/service/add_server.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,14 +7,14 @@
import rospy

def handle_add_two_ints(req):
print "Returning [%s + %s = %s]"%(req.a, req.b, (req.a + req.b))
print ("Returning [%s + %s = %s]"%(req.a, req.b, (req.a + req.b)))
return AddTwoIntsResponse(req.a + req.b)

def add_two_ints_server():
rospy.init_node('add_two_ints_server')
s = rospy.Service('add_two_ints', AddTwoInts, handle_add_two_ints)
print "Ready to add two ints."
print ("Ready to add two ints.")
rospy.spin()

if __name__ == "__main__":
add_two_ints_server()
add_two_ints_server()
8 changes: 8 additions & 0 deletions src/topic02_motion/turtlesim/clean.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@


<launch>
<node name="turtlesim" pkg="turtlesim" type="turtlesim_node" />
<node name="clean_node" pkg="ros_essentials_cpp" type="turtlesim_cleaner.py" />
</launch>


74 changes: 6 additions & 68 deletions src/topic02_motion/turtlesim/robot_cleaner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ void setDesiredOrientation (double desired_angle_radians);
void poseCallback(const turtlesim::Pose::ConstPtr & pose_message);
void moveGoal(turtlesim::Pose goal_pose, double distance_tolerance);
void gridClean();
void spiralClean();
void spiralClean(double rk, double wk);

int main(int argc, char **argv)
{
Expand All @@ -47,62 +47,13 @@ int main(int argc, char **argv)
velocity_publisher = n.advertise<geometry_msgs::Twist>("/turtle1/cmd_vel", 1000);
pose_subscriber = n.subscribe("/turtle1/pose", 10, poseCallback);

//ros::Rate loop_rate(10);



/** test your code here **/
ROS_INFO("\n\n\n******START TESTING************\n");
/*cout<<"enter speed: ";
cin>>speed;
cout<<"enter distance: ";
cin>>distance;
cout<<"forward?: ";
cin>>isForward;
move(speed, distance, isForward);

cout<<"enter angular velocity (degree/sec): ";
cin>>angular_speed;
cout<<"enter desired angle (degrees): ";
cin>>angle;
cout<<"clockwise ?: ";
cin>>clockwise;
rotate(degrees2radians(angular_speed), degrees2radians(angle), clockwise);
*/
ros::Rate loop_rate(0.5);
/*setDesiredOrientation(degrees2radians(120));

loop_rate.sleep();
setDesiredOrientation(degrees2radians(-60));
loop_rate.sleep();
setDesiredOrientation(degrees2radians(0));*/

/*turtlesim::Pose goal_pose;
goal_pose.x=1;
goal_pose.y=1;
goal_pose.theta=0;
moveGoal(goal_pose, 0.01);
loop_rate.sleep();
*/

//gridClean();
//loop.sleep();

ros::Rate loop(0.5);
turtlesim::Pose pose;
pose.x=1;
pose.y=1;
pose.theta=0;
moveGoal(pose, 0.01);

pose.x=6;
pose.y=6;
pose.theta=0;
moveGoal(pose, 0.01);



loop.sleep();
//spiralClean();
spiralClean(0,4);

ros::spin();

Expand Down Expand Up @@ -276,36 +227,23 @@ void gridClean(){
}


void spiralClean(){
void spiralClean(double rk, double wk){
geometry_msgs::Twist vel_msg;
double count =0;

double constant_speed=4;
double vk = 1;
double wk = 2;
double rk = 0.5;
ros::Rate loop(1);

do{
rk=rk+1.0;
vel_msg.linear.x =rk;
vel_msg.linear.y =0;
vel_msg.linear.z =0;
//set a random angular velocity in the y-axis
vel_msg.angular.x = 0;
vel_msg.angular.y = 0;
vel_msg.angular.z =constant_speed;//((vk)/(0.5+rk));
vel_msg.angular.z =wk;

cout<<"vel_msg.linear.x = "<<vel_msg.linear.x<<endl;
cout<<"vel_msg.angular.z = "<<vel_msg.angular.z<<endl;
velocity_publisher.publish(vel_msg);
ros::spinOnce();

loop.sleep();
//vk = vel_msg.linear.x;
//wk = vel_msg.angular.z;
//rk = vk/wk;
cout<<rk<<", "<<vk <<", "<<wk<<endl;

}while((turtlesim_pose.x<10.5)&&(turtlesim_pose.y<10.5));
vel_msg.linear.x =0;
velocity_publisher.publish(vel_msg);
Expand Down
97 changes: 37 additions & 60 deletions src/topic02_motion/turtlesim/turtlesim_cleaner.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,10 +7,6 @@
import time
from std_srvs.srv import Empty

x=0
y=0
yaw=0

def poseCallback(pose_message):
global x
global y, yaw
Expand All @@ -24,7 +20,7 @@ def poseCallback(pose_message):
#print ('yaw = {}'.format(pose_message.theta)) #new in python 3


def move(speed, distance, is_forward):
def move(velocity_publisher, speed, distance, is_forward):
#declare a Twist message to send velocity commands
velocity_message = Twist()
#get current location
Expand All @@ -39,19 +35,16 @@ def move(speed, distance, is_forward):

distance_moved = 0.0
loop_rate = rospy.Rate(10) # we publish the velocity at 10 Hz (10 times a second)
cmd_vel_topic='/turtle1/cmd_vel'
velocity_publisher = rospy.Publisher(cmd_vel_topic, Twist, queue_size=10)


while True :
rospy.loginfo("Turtlesim moves forwards")
velocity_publisher.publish(velocity_message)

loop_rate.sleep()

#rospy.Duration(1.0)

distance_moved = abs(0.5 * math.sqrt(((x-x0) ** 2) + ((y-y0) ** 2)))
print distance_moved
distance_moved = abs(math.sqrt(((x-x0) ** 2) + ((y-y0) ** 2)))
print (distance_moved)
print(x)
if not (distance_moved<distance):
rospy.loginfo("reached")
break
Expand All @@ -60,19 +53,10 @@ def move(speed, distance, is_forward):
velocity_message.linear.x =0
velocity_publisher.publish(velocity_message)

def rotate (angular_speed_degree, relative_angle_degree, clockwise):
def rotate (velocity_publisher, angular_speed_degree, relative_angle_degree, clockwise):

global yaw
velocity_message = Twist()
velocity_message.linear.x=0
velocity_message.linear.y=0
velocity_message.linear.z=0
velocity_message.angular.x=0
velocity_message.angular.y=0
velocity_message.angular.z=0

#get current location
theta0=yaw

angular_speed=math.radians(abs(angular_speed_degree))

if (clockwise):
Expand Down Expand Up @@ -106,20 +90,18 @@ def rotate (angular_speed_degree, relative_angle_degree, clockwise):
velocity_publisher.publish(velocity_message)


def go_to_goal(x_goal, y_goal):
def go_to_goal(velocity_publisher, x_goal, y_goal):
global x
global y, yaw

velocity_message = Twist()
cmd_vel_topic='/turtle1/cmd_vel'

while (True):
K_linear = 0.5
distance = abs(math.sqrt(((x_goal-x) ** 2) + ((y_goal-y) ** 2)))

linear_speed = distance * K_linear


K_angular = 4.0
desired_angle_goal = math.atan2(y_goal-y, x_goal-x)
angular_speed = (desired_angle_goal-yaw)*K_angular
Expand All @@ -128,57 +110,51 @@ def go_to_goal(x_goal, y_goal):
velocity_message.angular.z = angular_speed

velocity_publisher.publish(velocity_message)

#print velocity_message.linear.x
#print velocity_message.angular.z
print 'x=', x, 'y=',y

print ('x=', x, ', y=',y, ', distance to goal: ', distance)

if (distance <0.01):
break

def setDesiredOrientation(desired_angle_radians):
relative_angle_radians = desired_angle_radians - yaw
def setDesiredOrientation(publisher, speed_in_degree, desired_angle_degree):
relative_angle_radians = math.radians(desired_angle_degree) - yaw
clockwise=0
if relative_angle_radians < 0:
clockwise = 1
else:
clockwise = 0
print relative_angle_radians
print desired_angle_radians
rotate(30 ,math.degrees(abs(relative_angle_radians)), clockwise)
print ("relative_angle_radians: ",math.degrees(relative_angle_radians))
print ("desired_angle_degree: ",desired_angle_degree)
rotate(publisher, speed_in_degree,math.degrees(abs(relative_angle_radians)), clockwise)

def gridClean():
def gridClean(publisher):

desired_pose = Pose()
desired_pose.x = 1
desired_pose.y = 1
desired_pose.theta = 0

moveGoal(desired_pose, 0.01)
go_to_goal(publisher, 1,1)

setDesiredOrientation(degrees2radians(desired_pose.theta))
setDesiredOrientation(publisher, 30, math.radians(desired_pose.theta))

move(2.0, 9.0, True)
rotate(degrees2radians(20), degrees2radians(90), False)
move(2.0, 9.0, True)
rotate(degrees2radians(20), degrees2radians(90), False)
move(2.0, 1.0, True)
rotate(degrees2radians(20), degrees2radians(90), False)
move(2.0, 9.0, True)
rotate(degrees2radians(30), degrees2radians(90), True)
move(2.0, 1.0, True)
rotate(degrees2radians(30), degrees2radians(90), True)
move(2.0, 9.0, True)
for i in range(5):
move(publisher, 2.0, 1.0, True)
rotate(publisher, 20, 90, False)
move(publisher, 2.0, 9.0, True)
rotate(publisher, 20, 90, True)
move(publisher, 2.0, 1.0, True)
rotate(publisher, 20, 90, True)
move(publisher, 2.0, 9.0, True)
rotate(publisher, 20, 90, False)
pass



def spiralClean():
def spiralClean(velocity_publisher, wk, rk):
vel_msg = Twist()
loop_rate = rospy.Rate(1)
wk = 4
rk = 0

while((currentTurtlesimPose.x<10.5) and (currentTurtlesimPose.y<10.5)):
while((x<10.5) and (y<10.5)):
rk=rk+1
vel_msg.linear.x =rk
vel_msg.linear.y =0
Expand Down Expand Up @@ -208,10 +184,11 @@ def spiralClean():
pose_subscriber = rospy.Subscriber(position_topic, Pose, poseCallback)
time.sleep(2)

#move(1.0, 2.0, False)
#rotate(30, 90, True)
go_to_goal(1.0, 1.0)
#setDesiredOrientation(math.radians(90))

#move(velocity_publisher, 1.0, 9.0, True)
#rotate(velocity_publisher, 30, 90, True)
#go_to_goal(velocity_publisher, 2.0, 1.5)
#setDesiredOrientation(velocity_publisher, 30, 90)
#spiralClean(velocity_publisher, 4, 0)
gridClean(velocity_publisher)
except rospy.ROSInterruptException:
rospy.loginfo("node terminated.")
rospy.loginfo("node terminated.")
Loading