publish images usgin matlabros I/O package

500 views
Skip to first unread message

Abraham Ayala

unread,
Mar 4, 2014, 12:31:50 PM3/4/14
to ros-sig...@googlegroups.com
Hi guys:
I am using the rosmatlab I/O package released on january 2014. I am having problems when trying to publish an image from matlab to ROS. I am abble to read an image with the next code :
figure(1) 
            width = message.getWidth();
            height = message.getHeight();
            offset = message.getData().arrayOffset();
            indexR = offset+1:3:width*height*3+offset;
            indexG = indexR+1;
            indexB = indexG+1;
           
            imgCol = typecast(message.getData().array(), 'uint8');
            img = reshape([imgCol(indexR); imgCol(indexG); imgCol(indexB)], width, height, 3);
            img = permute(img, [2 1 3]);
            imshow(img);

the problem is if I want to publish it after defining :
pub = node.addPublisher('matlabimag','sensor_msgs/Image');
msg_im_pub = rosmatlab.message('sensor_msgs/Image', node);

if I try to do:

            msg_im_pub.setHeight(height);
            msg_im_pub.setWidth(width);
            msg_im_pub.setData().setArray(imgCol);

an error saying that "No method 'setData' with matching signature found for class 'org.ros.internal"
According to documentation, the setter and the getters are created by java, according to the difiniton of sensor_msgs/Image in http://docs.ros.org/api/sensor_msgs/html/msg/Image.html the message should have  a field "data". The get function aparently complies with this method but is strange that also has the fields arrayOffset() and array() that they not appear in the definition of the message.

I had tried autocomplete when debuggin and the method setData appears for msg_im_pub, so I dont know if I am configurig something wrong. I also had tried :
msg_im_pub.setData(ImgCol)
msg_im_pub.set.Data(ImgCol)

Can somebody give  a hint on how to publish the image from matlab to ROS?

Thanks

Gareth Thomas

unread,
Mar 5, 2014, 3:13:23 AM3/5/14
to ros-sig...@googlegroups.com
Hi Abraham,


The setData does method exist, but it is expecting a “org.jboss.netty.buffer.DuplicatedChannelBuffer” object as its argument. The easiest way to set the array is to use the getData method to return the object of the correct type, then set the relevant fields, and reuse the modified object as argument in setData.

 

The problem, of course, is that you have to know how to set the “array” data in the org.jboss.netty.buffer.DuplicatedChannelBuffer object. See http://docs.jboss.org/netty/3.2/api/org/jboss/netty/buffer/DuplicatedChannelBuffer.html on how to accomplish this. For demonstration purposes, I will use the setByte method

 

Try this:

roscore = rosmatlab.roscore(11311);

node = rosmatlab.node('NODE',roscore.RosMasterUri);

msg_im_pub = rosmatlab.message('sensor_msgs/Image', node);

imageData = msg_im_pub.getData()

imgCol = [0:127,0:127]'

for i = 1:numel(imgCol)

    imageData.setByte(int32(i-1),int32(imgCol(i)))

end

msg_im_pub.setData(imageData)

msg_im_pub.getData().array %notice the modified array

 

Hope this helps.


Best regards,

Gareth


PS - this would be also a good candidate to post on MATLAB Answers:)

http://www.mathworks.nl/matlabcentral/answers/




--
You received this message because you are subscribed to the Google Groups "ros-sig-matlab" group.
To unsubscribe from this group and stop receiving emails from it, send an email to ros-sig-matla...@googlegroups.com.
For more options, visit https://groups.google.com/groups/opt_out.

Remo Pillat

unread,
Mar 5, 2014, 8:12:47 AM3/5/14
to ros-sig...@googlegroups.com
Hi Abraham,

Just to add to Gareth's answer, I would like to give you a more extensive example of actually reading an image in MATLAB and then publishing it on a topic.
For the sake of the example, let's assume that your topic is named "/matlab_image" and you have an RGB image called "example_image.jpg" that you would like to publish:

roscore = rosmatlab.roscore(11311);

node = rosmatlab.node('NODE',roscore.RosMasterUri);

publisher = rosmatlab.publisher('/matlab_image','sensor_msgs/Image',node);

msg_im_pub = rosmatlab.message('sensor_msgs/Image', node);

 

% Read some image here

image = imread('example_image.jpg');

[height,width,channels] = size(image);

image = permute(image,[3 2 1]);     % Flip dimensions

image = image(:);                   % Vectorize

 

% Populate image message

msg_im_pub.setStep(width*channels);

msg_im_pub.setWidth(width);

msg_im_pub.setHeight(height);

msg_im_pub.setEncoding('rgb8');     % RGB image

msg_im_pub.setIsBigendian(false);

 

% Create java buffer to save the image array

messageBuffer = org.ros.internal.message.MessageBuffers.dynamicBuffer();

stream = org.jboss.netty.buffer.ChannelBufferOutputStream(messageBuffer);

stream.write(image);

msg_im_pub.setData(stream.buffer().copy());

stream.buffer().clear(); % Clear java buffer

 

publisher.publish(msg_im_pub);


The code will be slightly different if you are dealing with single-channel (grayscale) images, but it should definitely get you started.
Please let me know if this solves your problem or if you have any other questions.

Thanks,
Remo

Abraham Ayala

unread,
Mar 5, 2014, 10:04:00 AM3/5/14
to ros-sig...@googlegroups.com
Really thank you to both of you!
Remo your example was really illustrative and save me a lot of time of struggling with data types and creating the buffer. I appreciate a lot your help. It worked fine!!!
I will see to post this in mathworks answers if you don't mind.

Have a nice day and really thank you for your help!

Samarth Brahmbhatt

unread,
May 7, 2014, 6:49:58 PM5/7/14
to ros-sig...@googlegroups.com
Hi guys,

Thanks for the discussion so far! I am trying to publish a geometry_msgs/Polygon from Matlab and facing similar issues. A Polygon is an array of geometry_msgs/Point32's (like Image's data is an array of uint8's). I created a message of that type. The message object has a function called setPoints() but I can't figure out how use that function.

All attempts to create a separate geometry_msgs/Point32 message and pass it over, as well as copy a buffer (as in the case of Image) have resulted in the following error for me:

No method 'setPoints' with matching signature found for class 'org.ros.internal.message.$Proxy22'.

As you guys have probably figured out, I have no knowledge of Java. Any help would be greatly appreciated! An answer to this IMO will also be helpful for a lot of other custom message types too.

Samarth
Message has been deleted

Samarth Brahmbhatt

unread,
May 8, 2014, 12:56:55 AM5/8/14
to ros-sig...@googlegroups.com
Figured it out myself. The hint was in Gareth Thomas's answer - use the getPoints() function to see what the setPoints() expects. In this case, it expects a java.util.ArrayList. For the sake of completeness:

roscore = rosmatlab.roscore(11311);
n = rosmatlab.node('NODE', roscore.RosMasterUri);
poly = rosmatlab.message('geometry_msgs/Polygon', n);
p = poly.getPoints(); % java.util.ArrayList 

pt = rosmatlab.message('geometry_msgs/Point32', n);

pt.setX(77); pt.setY(77); pt.setZ(77);
p.add(pt); % First point of polygon - (77, 77, 77)

pt.setX(78); pt.setY(78); pt.setZ(78);
p.add(pt); % Second point of polygon - (78, 78, 78)

% Add more points similarly...

poly.setPoints(p);

Samarth 

Emily

unread,
Jan 12, 2015, 9:32:57 PM1/12/15
to ros-sig...@googlegroups.com

Nice to meet you. I am Emily from Germany.

I am using the RosMatlab I/O package released on january 2014. I am having problems when trying to publish a PoseArray from Matlab to Rviz. I can send the message from Matlab. But Rviz can’t display the PoseArray, because it doesn’t set the “frame_id” of header file. Unfortunately, I can’t fins the way how to set them on the below code. Could you teach me how to set the frame_id or header file on RosMatlab?

 

with the next code :

node = rosmatlab.node('PublishArray', [], [], 'rosIP', '127.0.0.1');

publisher = rosmatlab.publisher('TOPIC', 'geometry_msgs/PoseArray', node);

msg = rosmatlab.message('geometry_msgs/PoseArray', node);

po = rosmatlab.message('geometry_msgs/Pose', node);

p = msg.getPoses();

po.getPosition().setX(0); po.getPosition().setY(0); po.getPosition().setZ(0);

po.getOrientation().setX(0); po.getOrientation().setY(0); po.getOrientation().setZ(0); po.getOrientation().setW(0);

p.add(po);

msg.setPoses(p);

publisher.publish(msg);

 

If I run the above code, the below message comes on the rviz and can’t display the posearray..


“[ WARN] [1421107372.814210366]: Invalid argument passed to canTransform argument source_frame in tf2 frame_ids cannot be empty”

 

I would appreciate it very much if you could advise me anything.

Best regards,

Emily



2014年5月8日木曜日 6時56分55秒 UTC+2 Samarth Brahmbhatt:

Remo Pillat

unread,
Jan 14, 2015, 8:31:01 AM1/14/15
to ros-sig...@googlegroups.com
Hi Emily,

The "frame_id" is a string property that is part of the PoseArray's header. You can set it as follows (replace "frame_name" with the name of your desired coordinate frame):

      msg.getHeader.setFrameId('frame_name')

One more note: The quaternion orientation in your pose is not valid and Rviz might have trouble displaying it. Try setting the "W" value to 1, so that the quaternion is a unit vector, e.g.

      po.getOrientation().setW(1); 

Let me know if this works for you.

Thanks,
Remo
...

Emily

unread,
Jan 23, 2015, 8:14:55 PM1/23/15
to ros-sig...@googlegroups.com

Dear Mr. Remo,


Thank you for giving me the detailed information!! I could publish the posearray : )

Could I ask another question? Now, I also have a problem to set “time_from_start” when publish a JointTrajectory from Matlab.

Could you teach me how to set thetime_from_start” on RosMatlab?

 

with the next code :

 --------------------------------------------------------------------------------

node = rosmatlab.node('PublishTrajectory', [], [], 'rosIP', '127.0.0.1');

publisher = rosmatlab.publisher('Traj', 'trajectory_msgs/JointTrajectory', node);

 

msg = rosmatlab.message('trajectory_msgs/JointTrajectory', node);

po = rosmatlab.message('trajectory_msgs/JointTrajectoryPoint', node);

 

p1 = msg.getPoints();

po.setTimeFromStart(1);

p1.add(po);

 

msg.setPoints(p1);

publisher.publish(msg);

 ------------------------------------------------------------------------------------

If I run the above code, the below message comes on Matlab and can’t publish.

 

No method 'setTimeFromStart' with matching signature found for class 'org.ros.internal.message.$Proxy27'.

 

Error in JointTraj (line 27)

po.setTimeFromStart(1);

 

I would appreciate it very much if you could advise me anything.

 

Best regards,

Emily



2015年1月14日水曜日 14時31分01秒 UTC+1 Remo Pillat:

G.A. vd. Hoorn - 3ME

unread,
Jan 24, 2015, 5:54:17 AM1/24/15
to ros-sig...@googlegroups.com
On 24-1-2015 2:14, Emily wrote:
> Dear Mr. Remo,
>
> Thank you for giving me the detailed information!! I could publish the
> posearray : )
>
> Could I ask another question? Now, I also have a problem to set
> “time_from_start” when publish a JointTrajectory from Matlab.
>
> Could you teach me how to set the“time_from_start” on RosMatlab?
[..]

Also on ROS Answers:


http://answers.ros.org/question/201640/time_from_start-of-jointtrajectory-on-rosmatlab/

Remo Pillat

unread,
Jan 26, 2015, 10:06:12 AM1/26/15
to ros-sig...@googlegroups.com
Hi Emily,

As you can see in the message definition for trajectory_msgs/JointTrajectoryPoint, the "time_from_start" element has to be specified as a duration object.
There are two different ways how you can set the value of this duration object:
  • Create a new "org.ros.message.Duration" object, populate it with data and then assign the value in the original JointTrajectoryPoint message. For example, if you want to specify a duration of two (2) seconds:
           po = rosmatlab.message('trajectory_msgs/JointTrajectoryPoint', node);
           d = org.ros.message.Duration;
           d.secs = 2;
           po.setTimeFromStart(d)

  • Alternatively, you can assign the value directly to the time_from_start element. Note that since all Java objects in MATLAB are handle objects, you don't have to explicitly call the setTimeFromStart function, but you can modify the handle directly that getTimeFromStart returns.
    For example, if you want to specify a duration of three (3) seconds:
           po = rosmatlab.message('trajectory_msgs/JointTrajectoryPoint', node);
           d = po.getTimeFromStart;
           d.secs = 3;

Let me know if this solves your problem.

Thanks,
Remo


...

winwin...@gmail.com

unread,
Dec 21, 2017, 12:47:32 AM12/21/17
to ros-sig-matlab

玖富娱乐推荐主管QQ708227玖富娱乐推荐主管QQ708227

玖富娱乐推荐主管QQ708227玖富娱乐推荐主管QQ708227

Abraham Ayala於 2014年3月5日星期三 UTC+8上午1時31分50秒寫道:
Reply all
Reply to author
Forward
0 new messages