• image

      Autonomous Safe Landing UAV [ code ]

      Pointcloud processing, PX4, waypoint planner, RealSense D455, GPS-localization | ROS, C++

      Tools: Robot Operating System, Mavros, Pixhawk, PointCloud Library, Assembled Quadrotor

      Driven by the critical need for safer drone landings other than using fiducial markers, this project involves a quadrotor with an integrated Intel NUC onboard. It utilizes a downward facing Intel D455 stereo camera to capture point cloud data, processed with PCL algorithms like RANSAC for ground segmentation and obstacle detection. The 'Safe Landing Planner Node' assesses landing conditions and determines if it is safe for the UAV to land, while the 'Waypoint Node' guides the drone to land safely using the PX4 flight controller. The project integrates 3D cameras and advanced algorithms, providing a validated solution for emergency drone landings with ROS and PX4 software stack.

      • image
        Simulation
      • image
        Hardware
    • image

      3D Mapping and Localization in GPS-denied areas [ code ]

      Octomap, Pixhawk, Time Synchronization, Intel realsense D415 and T265 cameras, Velodyne Lidar | ROS, C++

      Tools: Robot Operating System, Mavros, Auterion VIO, PointCloud Library, Assembled Quadrotor

      Camera-based Mapping and Localization : In GPS-denied areas, where traditional GPS signals are unreliable or nonexistent, the integration of advanced mapping and localization technologies becomes essential. This project utlises intel realsense d415 depth camera to map the environment, and this builds an octomap voxel-grid based 3D mapping, further for localization I used the intel realsense t265 tracking camera to track features in the world and locate the system in a GPS-denied area. These both cameras are connected through ROS in the intel NUC system onboard. This system is vital for applications like indoor settings, urban canyons, and scenarios with signal interference, ensuring effective drone operation and autonomous systems in GPS-compromised conditions.

      • image
        VIO_Mapping_and_Localization

      Lidar-based Mapping and Localization : This project centers on enhancing drone mapping and localization by harnessing the Velodyne VLP-16 lidar sensor. Lidar data is processed to generate Octomaps that is voxel-grid based 3D mapping and this sensor has an intergrated IMU which allows it to have Localization easily. This will enable drones to create detailed maps and accurately locate themselves in outdoor GPS-denied environments.

      • image
        Lidar_Mapping_and_Localization
    • image

      PuSHR Perception [ Doc ]

      Deep Learning, Plane segmentation, 3D point Cloud Processing | Python

      Tools: MuSHR, RealSense D435i depth camera, Nvidia Jetson nano

      The Idea is to get the segmented RGB image and segment depth image respectively to obtain a segmented point cloud of the object of interest. This pointcloud could be pass to RANSAC to find out the best plane that has more number of points. Once the best plane is computed, we map it back to the pointcloud, through which we can map it back to the segmented RGB image. The obtained plane is shown in blue.

      • image
        PuSHR_Perception
    • image

      Robotic Arm - Planning and Avoidance [ code ]

      Rapidly-exploring Random Trees, Robotic Arm Kinematics, Motion Planning, Collision Avoidance | Python

      Tools: Pybullet, xArm 7 (Robotic Arm), Auterion VIO, Anaconda

      The project aims to leverage the xArm Python-SDK and PyBullet to control a simulated robotic arm to plan and avoida an obstacle in its path. An RRT-based planning was executed with Pybullet collision avoidance for the rnd-effector to reach its goal pose. The robotic arm manages to go from start pose to the goal pose after finding a suitable joint-trajectory. This can be optimised by either using RRT* or Bi-directional RRT.

      • image
        xArm_Planning_and_Avoidance
    • image

      V.I.K.R.A.M [ code ]

      Versatile Intelligent Kinetic Robot with Autonomous Manipulation

      2D Lidar SLAM, Self-Balancing, Design, Control, Robotic Arm Pick and Place | ROS, Python

      Tools: Robot Operating System, Solidworks, Gazebo, Moveit

      For a timely supply of emergency aid, we propose a technology-driven solution with minimal or no human intervention, i.e. a robot designed to accomplish different tasks. Since these are rare events, during the off-calamity time the robot can be used for an Industrial environment. VIKRAM is a versatile robot that is equipped with a Model Predictive Controller to balance itself on two wheels to either move in an industrial warehouse or move on uneven terrain. To work in industrial warehouses and to aid medical assistance in disaster scenarios, it is mounted with a robotic arm that explores the capabilities of pick and place operation using advanced perception techniques. The VIKRAM robot can also autonomously navigate to its desired location either in an industrial environment using SLAM algorithms or disaster scenarios using an obstacle avoidance algorithm.

      • image
        VIKRAM_Playlist
        image
        Vikram_Design
        image
        Vikram_Control
        image
        Vikram_Manipulation
        image
        Vikram_Navigation
    • image

      Robotics Competition - Self Balancing Robot [ code ]

      Mathematical Modelling, Sensor Fusion, Kalman Filtering, PID controllers | Python, Arduino

      Tools: Arduino Mega, Assembled Bot, Motor Driver, Zigbee Communication

      e-Yantra was a Nationwide Robotics Comptetion on different Robotic Tasks, My team was selected for the Self-Balancing Robot. This project's primary objective is to develop a self-balancing robot from scratch, we conceptualised, designed, modelled mathematically, sensor fusion till it is able to do all of its tasks. The Robot excels in traversing inclined surfaces and performing pick-and-drop tasks with exceptional accuracy. Achieving this goal involves integrating data from motor position encoders and an Inertial Measurement Unit (IMU), refining it using Kalman filtering for improved stability. Utilizing the Arduino Mega as the core controller and Zigbee for communication, this robotic system exhibits versatility and dependability, opening up a range of potential applications in logistics, surveillance, and various other domains.

      • image
        e_Yantra_Competition
        image
        Positon_Hold
        image
        Follow_Line
        image
        Traverse_Bridges
    • image

      First Robotics Project - Robotic Arm Imitation [ code ]

      OpenCV, Serial Communication, Computer Vision, 3D printing | Python

      Tools: Arduino, Assembled Robotic Arm, Servo Motors

      The project integrates a 3D-printed robotic arm with five servo motors, controlled by OpenCV's gesture recognition. Users' hand gestures, captured by a webcam, are processed by OpenCV to determine finger count. This data is relayed to an Arduino Uno, which commands the servo motors to mimic the gestures, enabling interactive communication. This project enhances human-robot interaction, promising versatile applications in education and beyond.

      • image
        Robotic_Arm_Imitation