0
$\begingroup$

Rosanswers logo

my source code is this

#include <ros/ros.h>
#include <tf/transform_broadcaster.h>
#include <tf/transform_listener.h>

#include <geometry_msgs/PointStamped.h>

#include <pcl_ros/point_cloud.h>
#include <pcl_ros/transforms.h>
#include <jsk_recognition_msgs/BoundingBoxArray.h>
#include <pharos_msgs/object_custom_msg.h>
#include <pharos_msgs/object_custom_msgs.h>
///전역변수///

///------////


class velodyne_
{
public:

    ros::NodeHandlePtr nh;
    ros::NodeHandlePtr pnh;


    velodyne_()
    {
        nh = ros::NodeHandlePtr(new ros::NodeHandle(""));
        pnh = ros::NodeHandlePtr(new ros::NodeHandle("~"));

        ///서브스크라이브는 this 사용 publish는 메세지형식 이것만 잘 생각해놓기
        sub_custom_msg = nh->subscribe("pharos_object_msg", 10 , &velodyne_::BOX_CB,this);
        pub_box_msg = nh->advertise<jsk_recognition_msgs::BoundingBoxArray>("object_box",10);

    }



    void BOX_CB(const pharos_msgs::object_custom_msgs &input_msg){
        ///CALLBACK 함수
        jsk_recognition_msgs::BoundingBoxArray BOXS;
            for(int i=0; i<input_msg.objects.size(); i++){
                jsk_recognition_msgs::BoundingBox box;
                box.label = i+1;
                box.pose.position.x = input_msg.objects[i].min_x;
                box.pose.position.y = input_msg.objects[i].min_y;
                box.pose.position.z = input_msg.objects[i].min_z;
                box.dimensions.x = input_msg.objects[i].max_x;
                box.dimensions.y = input_msg.objects[i].max_y;
                box.dimensions.z = input_msg.objects[i].max_z;

                box.header.frame_id ="velodyne";
                box.header.stamp = input_msg.header.stamp;
                BOXS.boxes.push_back(box);

            }


        BOXS.header.stamp=input_msg.header.stamp;
        BOXS.header.frame_id = "velodyne";

        pub_box_msg.publish(BOXS);

    }


protected:
    ros::Subscriber sub_custom_msg;
    ros::Publisher pub_box_msg;


};

int main(int argc, char **argv)
{

    ros::init(argc, argv, "object_box");       //노드명 초기화



    ROS_INFO("started object_box");
    ROS_INFO("SUBTOPIC : ");
    ROS_INFO("PUBTOPIC : ");

    velodyne_ hello;

    ros::spin();


}

i want to show up box with object ex) image description

i know min_x,y,z , max_x,y,z so i have 8 points of bound box how i can bounding object with jsk msg? i can publish some image but doesnt match size and position image description


Originally posted by dnjsxor564 on ROS Answers with karma: 11 on 2018-08-19

Post score: 0

$\endgroup$

1 Answer 1

0
$\begingroup$

Rosanswers logo

You are filling the box incorrectly, if you look at boundingBox , you need to give pose (position) that will be the centre point of box, and dimensions that will be the length, width and height of box.

It should look like following:

box.pose.position.x = (max_x + min_x)  / 2;
box.pose.position.y = (max_y + min_y)  / 2;
box.pose.position.z = (max_z + min_z)  / 2;
box.dimensions.x = (max_x - min_x);
box.dimensions.y = (max_y - min_y);
box.dimensions.z = (max_z - min_z);

This should solve it.


Originally posted by Choco93 with karma: 685 on 2018-08-21

This answer was ACCEPTED on the original site

Post score: 0


Original comments

Comment by dnjsxor564 on 2018-08-22:
thank you!! it is helpful to me!!

Comment by Choco93 on 2018-08-22:
if it solved your issue kindly mark the answer as correct/accepted

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.