forked from shehzi001/ros_foundation_course
-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
added ros pubisher and subscriber demo codes
- Loading branch information
Showing
67 changed files
with
2,038 additions
and
0 deletions.
There are no files selected for viewing
36 changes: 36 additions & 0 deletions
36
...als/demo_ros_publishers_subscribers/ros_publisher_common_msgs_cpp_examples/CMakeLists.txt
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,36 @@ | ||
cmake_minimum_required(VERSION 2.8.3) | ||
project(ros_publisher_common_msgs_cpp_examples) | ||
|
||
find_package(catkin REQUIRED COMPONENTS | ||
geometry_msgs | ||
actionlib_msgs | ||
nav_msgs | ||
sensor_msgs | ||
trajectory_msgs | ||
roscpp | ||
) | ||
|
||
catkin_package( | ||
CATKIN_DEPENDS | ||
geometry_msgs | ||
actionlib_msgs | ||
nav_msgs | ||
sensor_msgs | ||
trajectory_msgs | ||
roscpp | ||
) | ||
|
||
|
||
include_directories( | ||
${catkin_INCLUDE_DIRS} | ||
ros/include | ||
) | ||
|
||
add_executable(publisher_common_messages_examples | ||
ros/src/publisher_common_messages_example_node.cpp | ||
ros/src/demo_class_example.cpp | ||
) | ||
|
||
target_link_libraries(publisher_common_messages_examples | ||
${catkin_LIBRARIES} | ||
) |
26 changes: 26 additions & 0 deletions
26
...orials/demo_ros_publishers_subscribers/ros_publisher_common_msgs_cpp_examples/package.xml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,26 @@ | ||
<?xml version="1.0"?> | ||
<package> | ||
<name>ros_publisher_common_msgs_cpp_examples</name> | ||
<version>0.1.0</version> | ||
<description>The ros_publisher_common_msgs_cpp_examples package</description> | ||
|
||
<maintainer email="[email protected]">Shehzad Ahmed</maintainer> | ||
|
||
<license>GPLv3</license> | ||
|
||
<buildtool_depend>catkin</buildtool_depend> | ||
<build_depend>roscpp</build_depend> | ||
<run_depend>roscpp</run_depend> | ||
|
||
<build_depend>geometry_msgs</build_depend> | ||
<build_depend>actionlib_msgs</build_depend> | ||
<build_depend>nav_msgs</build_depend> | ||
<build_depend>sensor_msgs</build_depend> | ||
<build_depend>trajectory_msgs</build_depend> | ||
|
||
<run_depend>geometry_msgs</run_depend> | ||
<run_depend>actionlib_msgs</run_depend> | ||
<run_depend>nav_msgs</run_depend> | ||
<run_depend>sensor_msgs</run_depend> | ||
<run_depend>trajectory_msgs</run_depend> | ||
</package> |
86 changes: 86 additions & 0 deletions
86
...msgs_cpp_examples/ros/include/ros_publisher_common_msgs_cpp_examples/demo_class_example.h
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,86 @@ | ||
/** | ||
* demo_class_example.h | ||
* | ||
* Created on: September 08, 2014 | ||
* Author: Shehzad Ahmed | ||
**/ | ||
#ifndef DEMO_CLASS_EXAMPLE_H_ | ||
#define DEMO_CLASS_EXAMPLE_H_ | ||
#include <ros/ros.h> | ||
|
||
#include <geometry_msgs/Point.h> | ||
#include <geometry_msgs/PointStamped.h> | ||
#include <geometry_msgs/Pose2D.h> | ||
#include <geometry_msgs/PoseWithCovariance.h> | ||
#include <geometry_msgs/TwistWithCovariance.h> | ||
#include <geometry_msgs/PoseStamped.h> | ||
#include <geometry_msgs/Twist.h> | ||
#include <geometry_msgs/Transform.h> | ||
#include <actionlib_msgs/GoalID.h> | ||
#include <nav_msgs/Odometry.h> | ||
#include <sensor_msgs/LaserScan.h> | ||
#include <sensor_msgs/Range.h> | ||
#include <trajectory_msgs/JointTrajectoryPoint.h> | ||
|
||
class DemoClass | ||
{ | ||
public: | ||
/** | ||
* Ctor. | ||
*/ | ||
DemoClass(const ros::NodeHandle &nh); | ||
|
||
/** | ||
* Ctor. | ||
*/ | ||
virtual ~DemoClass(); | ||
|
||
/** | ||
* prepare example ros messages. | ||
*/ | ||
void prepareAndPublishMsgs(); | ||
void prepareAndPublishGeometryMsg(); | ||
void prepareAndPublishActionlibMsg(); | ||
void prepareAndPublishOdometryMsg(); | ||
void prepareAndPublishLaserScanMsg(); | ||
void prepareAndPublishRangeMsg(); | ||
void prepareAndPublishJointTrajectoyPointMsg(); | ||
|
||
private: | ||
/* | ||
* Instantiation of ROS node handle | ||
*/ | ||
ros::NodeHandle nh_; | ||
|
||
/* | ||
* Instantiation of common messages | ||
*/ | ||
geometry_msgs::Point point_message_; | ||
geometry_msgs::PointStamped pointstamped_message_; | ||
geometry_msgs::Pose2D pose2d_message_; | ||
geometry_msgs::PoseStamped posestamped_message_; | ||
geometry_msgs::Twist twist_message_; | ||
geometry_msgs::Transform transform_message_; | ||
|
||
actionlib_msgs::GoalID goal_id_message_; | ||
nav_msgs::Odometry odomety_message_; | ||
sensor_msgs::LaserScan laser_scan_message_; | ||
sensor_msgs::Range range_message_; | ||
trajectory_msgs::JointTrajectoryPoint joint_trajectory_point_message_; | ||
|
||
/* | ||
* Instantiation of common_msg publishers | ||
*/ | ||
ros::Publisher point_msg_pub_; | ||
ros::Publisher pointstamped_msg_pub_; | ||
ros::Publisher pose2d_msg_pub_; | ||
ros::Publisher posestamped_msg_pub_; | ||
ros::Publisher twist_msg_pub_; | ||
ros::Publisher transform_msg_pub_; | ||
|
||
ros::Publisher actionlib_msg_pub_; | ||
ros::Publisher odometry_msg_pub_; | ||
ros::Publisher laserScan_msg_pub_; | ||
ros::Publisher joint_traj_point_msg_pub_; | ||
}; | ||
#endif /** DEMO_CLASS_EXAMPLE_H_ **/ |
197 changes: 197 additions & 0 deletions
197
...lishers_subscribers/ros_publisher_common_msgs_cpp_examples/ros/src/demo_class_example.cpp
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,197 @@ | ||
/** | ||
* demo_class_example.cpp | ||
* | ||
* Created on: September 08, 2014 | ||
* Author: Shehzad Ahmed | ||
**/ | ||
|
||
#include <ros_publisher_common_msgs_cpp_examples/demo_class_example.h> | ||
|
||
DemoClass::DemoClass(const ros::NodeHandle &nh): | ||
nh_(nh) | ||
{ | ||
|
||
point_msg_pub_ = nh_.advertise<geometry_msgs::Point>("point", 100); | ||
pointstamped_msg_pub_ = nh_.advertise<geometry_msgs::PointStamped>("stamped_point", 100); | ||
twist_msg_pub_ = nh_.advertise<geometry_msgs::Twist>("twist", 100); | ||
|
||
/* | ||
* Please, prepare the topics for the following messages: | ||
* PoseStamped, Pose2D, Transform, GoalID, Odometry | ||
* LaserScan, Range, JointTrajectoryPoint | ||
* | ||
* Topic names are: | ||
* posestamped_msg_pub_ | ||
* pose2d_msg_pub_ | ||
* transform_msg_pub_ | ||
* actionlib_msg_pub_ | ||
* odometry_msg_pub_ | ||
* laserScan_msg_pub_ | ||
* joint_traj_point_msg_pub_ | ||
*/ | ||
} | ||
|
||
|
||
DemoClass::~DemoClass() | ||
{ | ||
} | ||
|
||
void DemoClass::prepareAndPublishMsgs() | ||
{ | ||
prepareAndPublishGeometryMsg(); | ||
prepareAndPublishActionlibMsg(); | ||
prepareAndPublishOdometryMsg(); | ||
prepareAndPublishLaserScanMsg(); | ||
prepareAndPublishRangeMsg(); | ||
prepareAndPublishJointTrajectoyPointMsg(); | ||
} | ||
|
||
void DemoClass::prepareAndPublishGeometryMsg() | ||
{ | ||
/* | ||
* Filling point message | ||
*/ | ||
point_message_.x = 1.0; | ||
point_message_.y = 1.0; | ||
point_message_.z = 1.0; | ||
|
||
point_msg_pub_.publish(point_message_); | ||
|
||
/* | ||
* Filling twist message. | ||
* Specify Robot velocity in the x-direction | ||
* with 1.0 rad/sec. | ||
*/ | ||
twist_message_.linear.x = 1.0; | ||
twist_message_.linear.y = 0.0; | ||
twist_message_.linear.z = 0.0; | ||
|
||
twist_message_.angular.x = 0.0; | ||
twist_message_.angular.y = 0.0; | ||
twist_message_.angular.z = 0.0; | ||
|
||
twist_msg_pub_.publish(twist_message_); | ||
|
||
/* | ||
* Filling point stamped | ||
*/ | ||
pointstamped_message_.header.stamp = ros::Time::now(); | ||
pointstamped_message_.header.frame_id = "frame_dummy"; | ||
|
||
pointstamped_message_.point.x = 1.0; | ||
pointstamped_message_.point.y = 1.0; | ||
pointstamped_message_.point.z = 1.0; | ||
|
||
pointstamped_msg_pub_.publish(pointstamped_message_); | ||
|
||
/* | ||
* Filling Transform message | ||
* Do it your self for practice | ||
*/ | ||
|
||
/* | ||
* Filling pose2d message | ||
* Do it your self for practice | ||
*/ | ||
|
||
/* | ||
* Filling posestamped message | ||
* Do it your self for practice | ||
*/ | ||
} | ||
|
||
|
||
void DemoClass::prepareAndPublishActionlibMsg() | ||
{ | ||
/* | ||
* Filling goal_id message | ||
*/ | ||
goal_id_message_.stamp = ros::Time::now(); | ||
goal_id_message_.id = "ACTIVE"; | ||
} | ||
|
||
|
||
void DemoClass::prepareAndPublishOdometryMsg() | ||
{ | ||
/* | ||
* nav_msgs example. | ||
* Filling odom message. | ||
* Step 1: Prepare pose and twist messages separatly. | ||
* Step 2: Fill the data in actual message odomety_message_. | ||
*/ | ||
geometry_msgs::PoseWithCovariance pose; | ||
geometry_msgs::TwistWithCovariance twist; | ||
|
||
/* | ||
odomety_message_.header.stamp = ros::Time::now();; | ||
odomety_message_.header.frame_id = "odom_frame"; | ||
odomety_message_.child_frame_id = "base_frame"; | ||
odomety_message_.pose = pose; | ||
odomety_message_.twist = twist; | ||
odomety_message_.covariance = 0.5; | ||
*/ | ||
} | ||
|
||
|
||
void DemoClass::prepareAndPublishLaserScanMsg() | ||
{ | ||
/* | ||
* sensor_msgs example | ||
* Filling laser scan message | ||
* Step 1: Prepare data to be filled | ||
* Step 2: Fill actual message with the prepared data. | ||
*/ | ||
|
||
//Step 1: | ||
unsigned int num_readings = 15; | ||
double laser_frequency = 40; | ||
double ranges[num_readings]; | ||
double intensities[num_readings]; | ||
int count = 0; | ||
|
||
//generate some fake data for laser scan | ||
for (unsigned int i = 0; i < num_readings; ++i) { | ||
ranges[i] = count; | ||
intensities[i] = 4 + count; | ||
} | ||
|
||
//Step 2 | ||
laser_scan_message_.header.stamp = ros::Time::now(); | ||
laser_scan_message_.header.frame_id = "laser_frame"; | ||
laser_scan_message_.angle_min = -1.57; | ||
laser_scan_message_.angle_max = 1.57; | ||
laser_scan_message_.angle_increment = 3.14 / num_readings; | ||
laser_scan_message_.time_increment = (1 / laser_frequency) / (num_readings); | ||
laser_scan_message_.range_min = 0.0; | ||
laser_scan_message_.range_max = 4.0; | ||
|
||
laser_scan_message_.ranges.resize(num_readings); | ||
laser_scan_message_.intensities.resize(num_readings); | ||
for (unsigned int i = 0; i < num_readings; ++i) { | ||
laser_scan_message_.ranges[i] = ranges[i]; | ||
laser_scan_message_.intensities[i] = intensities[i]; | ||
} | ||
} | ||
|
||
|
||
void DemoClass::prepareAndPublishRangeMsg() | ||
{ | ||
/* | ||
* sensor_msgs example | ||
* Filling range messages | ||
* Do it your self for practice | ||
* Message to be filled is range_message_ | ||
*/ | ||
} | ||
|
||
void DemoClass::prepareAndPublishJointTrajectoyPointMsg() | ||
{ | ||
/* | ||
* trajectory_msgs example | ||
* Filling JointTrajectoyPoint message | ||
* Do it your self for practice | ||
* Step 1: Prepare data to be filled | ||
* Step 2: Fill actual message with the prepared data. | ||
* Message to be filled is joint_trajectory_point_message_. | ||
*/ | ||
} |
45 changes: 45 additions & 0 deletions
45
...ros_publisher_common_msgs_cpp_examples/ros/src/publisher_common_messages_example_node.cpp
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,45 @@ | ||
/** | ||
* common_messages_example_node.cpp | ||
* | ||
* Created on: September 08, 2014 | ||
* Author: Shehzad Ahmed | ||
**/ | ||
|
||
#include <ros/ros.h> | ||
#include "ros_publisher_common_msgs_cpp_examples/demo_class_example.h" | ||
|
||
|
||
int main(int argc, char *argv[]) | ||
{ | ||
/** | ||
* Initilization of node | ||
**/ | ||
ros::init(argc, argv, "publiher_common_messages_example_node"); | ||
|
||
/** | ||
* Initilization of private node handle | ||
**/ | ||
ros::NodeHandle nh("~"); | ||
|
||
/** | ||
* Printing Information message on the console. | ||
**/ | ||
ROS_INFO("publiher_common_messages_example_node is now running"); | ||
|
||
ros::Rate loop_rate(10); | ||
|
||
DemoClass demo_class(nh); | ||
|
||
/** | ||
* Keep loop untill the user node is killed. | ||
**/ | ||
ROS_INFO("Press Cntrl+c to kill the node."); | ||
while(ros::ok()) { | ||
demo_class.prepareAndPublishMsgs(); | ||
ros::spinOnce(); | ||
loop_rate.sleep(); | ||
} | ||
|
||
|
||
return 0; | ||
} |
Oops, something went wrong.